Apollo 10.0
自动驾驶开放平台
apollo::perception::radar4d 命名空间参考

命名空间

namespace  pointpillars
 
namespace  util
 

class  AnchorMaskCuda
 
class  BaseBipartiteGraphMatcher
 
class  BaseClassifier
 
class  BaseDetector
 
class  BaseMultiTargetTracker
 
class  BaseOneShotTypeFusion
 
class  BasePreprocessor
 
class  BaseRadarObstaclePerception
 
class  BaseRoiFilter
 
class  BaseSequenceTypeFusion
 
struct  BipartiteGraphMatcherInitOptions
 
struct  BipartiteGraphMatcherOptions
 
class  CCRFOneShotTypeFusion
 
class  CCRFSequenceTypeFusion
 
struct  CcrfTypeFusionConfig
 
struct  ClassifierInitOptions
 
struct  ClassifierOptions
 
struct  DetectorInitOptions
 
struct  DetectorOptions
 
class  FeatureDescriptor
 
class  FusedClassifier
 
struct  FusedClassifierConfig
 
class  GnnBipartiteGraphMatcher
 
class  HdmapRadarRoiFilter
 
class  Logger
 
class  MatchCost
 
class  MrfBaseFilter
 
struct  MrfDistanceConfig
 
struct  MrfDistanceWeight
 
class  MrfEngine
 
struct  MrfEngineConfig
 
struct  MrfFilterInitOptions
 
struct  MrfFilterOptions
 
class  MrfMotionFilter
 
struct  MrfMotionFilterConfig
 
class  MrfMotionMeasurement
 
class  MrfMotionRefiner
 
struct  MrfMotionRefinerConfig
 
struct  MrfMotionRefinerInitOptions
 
struct  MrfMotionRefinerOptions
 
struct  MrfPredict
 
class  MrfShapeFilter
 
struct  MrfShapeFilterConfig
 
class  MrfTrackData
 
struct  MrfTrackDataInitializer
 
class  MrfTracker
 
struct  MrfTrackerConfig
 
struct  MrfTrackerInitOptions
 
class  MrfTrackObjectDistance
 
struct  MrfTrackObjectDistanceInitOptions
 
class  MrfTrackObjectMatcher
 
struct  MrfTrackObjectMatcherConfig
 
struct  MrfTrackObjectMatcherInitOptions
 
struct  MrfTrackObjectMatcherOptions
 
struct  MrfTrackOptions
 
class  MultiHmBipartiteGraphMatcher
 
struct  MultiTargetTrackerInitOptions
 
struct  MultiTargetTrackerOptions
 
class  NmsCuda
 
class  ObjectBuilder
 
class  ObjectSequence
 
class  Params
 
struct  PerceptionInitOptions
 
class  PfeCuda
 
class  PointPillars
 
class  PostprocessCuda
 
struct  PreprocessorConfig
 
struct  PreprocessorInitOptions
 
struct  PreprocessorOptions
 
class  PreprocessPoints
 
class  PreprocessPointsCuda
 
class  Radar4dDetection
 
class  Radar4dDetectionComponent
 
struct  Radar4dDetectionConfig
 
struct  RadarFrame
 
struct  RadarFrameInitializer
 
class  RadarObstaclePerception
 
struct  RadarObstaclePerceptionConfig
 
struct  RadarPerceptionOptions
 
class  RadarPreprocessor
 
struct  RoiFilterInitOptions
 
struct  RoiFilterOptions
 
class  ScatterCuda
 
class  Timer
 
class  TrackData
 
struct  TrackDataInitializer
 
struct  TrackedObject
 
struct  TrackedObjectInitializer
 
struct  TypeFusionInitOption
 
struct  TypeFusionOption
 

类型定义

using ObjectPtr = std::shared_ptr< apollo::perception::base::Object >
 
typedef base::ConcurrentObjectPool< RadarFrame, kRadarFramePoolSize, RadarFrameInitializerRadarFramePool
 
typedef Eigen::Matrix< double, VALID_OBJECT_TYPE, 1 > Vectord
 
typedef Eigen::Matrix< int, VALID_OBJECT_TYPE, 1 > Vectori
 
typedef Eigen::Matrix< double, VALID_OBJECT_TYPE, VALID_OBJECT_TYPEMatrixd
 
using RadarPointFCloud = apollo::perception::base::RadarPointCloud< RadarPointF >
 
typedef std::shared_ptr< MrfTrackDataMrfTrackDataPtr
 
typedef std::shared_ptr< const MrfTrackDataMrfTrackDataConstPtr
 
typedef std::shared_ptr< TrackDataTrackDataPtr
 
typedef std::shared_ptr< const TrackDataTrackDataConstPtr
 
typedef base::ConcurrentObjectPool< TrackedObject, kTrackedObjectPoolSize, TrackedObjectInitializerTrackedObjectPool
 
typedef base::ConcurrentObjectPool< TrackData, kTrackDataPoolSize, TrackDataInitializerTrackDataPool
 
typedef base::ConcurrentObjectPool< MrfTrackData, kTrackDataPoolSize, MrfTrackDataInitializerMrfTrackDataPool
 
typedef std::shared_ptr< TrackedObjectTrackedObjectPtr
 
typedef std::shared_ptr< const TrackedObjectTrackedObjectConstPtr
 

枚举

enum  { VALID_OBJECT_TYPE = static_cast<int>(base::ObjectType::MAX_OBJECT_TYPE) - 2 }
 
enum class  MotionState { STATIC = 0 , SKEPTICAL_MOVE = 1 , TRUSTED_MOVE = 2 }
 

函数

 __attribute__ ((constructor)) void RadarFramePoolInitialize()
 
void GetBoundingBox2d (const std::shared_ptr< Object > &object, RadarPointCloud< RadarPointD > *box, double expand)
 
void ComputeObjectShapeFromPolygon (std::shared_ptr< Object > object, bool use_world_cloud)
 
void GetBoundingBox2d (const std::shared_ptr< base::Object > &object, base::RadarPointCloud< base::RadarPointD > *box, double expand=0.0)
 
void ComputeObjectShapeFromPolygon (std::shared_ptr< base::Object > object, bool use_world_cloud=false)
 
 PERCEPTION_REGISTER_RADAR_OBSTACLE_PERCEPTION (RadarObstaclePerception)
 
 PERCEPTION_REGISTER_REGISTERER (BaseBipartiteGraphMatcher)
 
 PERCEPTION_REGISTER_REGISTERER (BaseClassifier)
 
 PERCEPTION_REGISTER_REGISTERER (BaseDetector)
 
 PERCEPTION_REGISTER_REGISTERER (BaseMultiTargetTracker)
 
 PERCEPTION_REGISTER_REGISTERER (BaseRadarObstaclePerception)
 
 PERCEPTION_REGISTER_REGISTERER (BasePreprocessor)
 
 PERCEPTION_REGISTER_REGISTERER (BaseRoiFilter)
 
 PERCEPTION_REGISTER_ONESHOTTYPEFUSION (CCRFOneShotTypeFusion)
 
 PERCEPTION_REGISTER_SEQUENCETYPEFUSION (CCRFSequenceTypeFusion)
 
 PERCEPTION_REGISTER_CLASSIFIER (FusedClassifier)
 
 PERCEPTION_REGISTER_REGISTERER (BaseOneShotTypeFusion)
 
 PERCEPTION_REGISTER_REGISTERER (BaseSequenceTypeFusion)
 
void GPUAssert (cudaError_t code, const char *file, int line, bool abort=true)
 
 PERCEPTION_REGISTER_DETECTOR (Radar4dDetection)
 
 PERCEPTION_REGISTER_PREPROCESSOR (RadarPreprocessor)
 
 PERCEPTION_REGISTER_ROI_FILTER (HdmapRadarRoiFilter)
 
float LocationDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
 Compute location distance for given track & object
 
float DirectionDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
 Compute direction distance for given track & object
 
float BboxSizeDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
 Compute bbox size distance for given track & object
 
float PointNumDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
 Compute point num distance for given track & object
 
float HistogramDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff)
 Compute histogram distance for given track & object
 
float CentroidShiftDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &cur_obj, const double time_diff)
 Compute centroid shift distance for object and background match
 
float BboxIouDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &cur_obj, const double time_diff, double match_threshold)
 Compute bbox iou distance for object and background match
 
bool operator< (const MatchCost &m1, const MatchCost &m2)
 
std::ostream & operator<< (std::ostream &os, const MatchCost &m)
 
 PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER (GnnBipartiteGraphMatcher)
 
 PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER (MultiHmBipartiteGraphMatcher)
 
void RemoveStaleDataFromMap (double timestamp, std::map< double, TrackedObjectPtr > *data)
 
void MeasureAnchorPointVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff)
 Measure anchor point velocity
 
void MeasureBboxCenterVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff)
 Measure bbox center velocity
 
void MeasureBboxCornerVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff)
 Measure bbox corner velocity
 
 PERCEPTION_REGISTER_REGISTERER (MrfBaseFilter)
 
void convertPoseToLoc (const Eigen::Affine3d &pose, localization::LocalizationEstimate *localization)
 
 PERCEPTION_REGISTER_MULTITARGET_TRACKER (MrfEngine)
 
 PERCEPTION_REGISTER_MRFFILTER (MrfMotionFilter)
 
 PERCEPTION_REGISTER_MRFFILTER (MrfShapeFilter)
 
 CYBER_REGISTER_COMPONENT (Radar4dDetectionComponent)
 

变量

struct apollo::perception::radar4d::TrackedObject EIGEN_ALIGN16
 

类型定义说明

◆ Matrixd

在文件 util.h40 行定义.

◆ MrfTrackDataConstPtr

在文件 mrf_track_data.h173 行定义.

◆ MrfTrackDataPool

◆ MrfTrackDataPtr

在文件 mrf_track_data.h172 行定义.

◆ ObjectPtr

◆ RadarFramePool

◆ RadarPointFCloud

◆ TrackDataConstPtr

在文件 track_data.h151 行定义.

◆ TrackDataPool

◆ TrackDataPtr

在文件 track_data.h150 行定义.

◆ TrackedObjectConstPtr

在文件 tracked_object.h206 行定义.

◆ TrackedObjectPool

◆ TrackedObjectPtr

在文件 tracked_object.h205 行定义.

◆ Vectord

typedef Eigen::Matrix<double, VALID_OBJECT_TYPE, 1> apollo::perception::radar4d::Vectord

在文件 util.h38 行定义.

◆ Vectori

在文件 util.h39 行定义.

枚举类型说明

◆ anonymous enum

anonymous enum
枚举值
VALID_OBJECT_TYPE 

在文件 util.h34 行定义.

34 {
35 VALID_OBJECT_TYPE = static_cast<int>(base::ObjectType::MAX_OBJECT_TYPE) - 2
36};

◆ MotionState

枚举值
STATIC 
SKEPTICAL_MOVE 
TRUSTED_MOVE 

在文件 track_data.h29 行定义.

29 {
30 STATIC = 0,
31 SKEPTICAL_MOVE = 1,
32 TRUSTED_MOVE = 2,
33};

函数说明

◆ __attribute__()

apollo::perception::radar4d::__attribute__ ( (constructor)  )

在文件 radar_frame_pool.cc23 行定义.

23 {
24 RadarFramePool::Instance();
25 AINFO << "Initialize radar frame pool.";
26}
#define AINFO
Definition log.h:42

◆ BboxIouDistance()

float apollo::perception::radar4d::BboxIouDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr cur_obj,
const double  time_diff,
double  match_threshold 
)

Compute bbox iou distance for object and background match

参数
last_objectobject for computing distance
track_predictunused
cur_objnew detected object for computing distance
time_diffunused
match_thresholdmatch threshold
返回
float distance

在文件 distance_collection.cc190 行定义.

193 {
194 // Step 1: unify bbox direction, change the one with less pts,
195 // for efficiency.
196 Eigen::Vector3f old_dir = last_object->output_direction.cast<float>();
197 Eigen::Vector3f old_size = last_object->output_size.cast<float>();
198 Eigen::Vector3d old_center = last_object->output_center;
199 Eigen::Vector3f new_dir = new_object->direction.cast<float>();
200 Eigen::Vector3f new_size = new_object->size.cast<float>();
201 Eigen::Vector3d new_center = new_object->center;
202 old_dir.normalize();
203 new_dir.normalize();
204 // handle randomness
205 old_size(0) = old_size(0) > 0.3f ? old_size(0) : 0.3f;
206 old_size(1) = old_size(1) > 0.3f ? old_size(1) : 0.3f;
207 new_size(0) = new_size(0) > 0.3f ? new_size(0) : 0.3f;
208 new_size(1) = new_size(1) > 0.3f ? new_size(1) : 0.3f;
209 int last_object_num_pts = static_cast<int>(
210 (last_object->object_ptr->radar4d_supplement).cloud_world.size());
211 int cur_obj_num_pts = static_cast<int>(
212 (new_object->object_ptr->radar4d_supplement).cloud_world.size());
213 bool change_cur_obj_bbox = last_object_num_pts > cur_obj_num_pts;
214 float minimum_edge_length = 0.01f;
216 (new_object->object_ptr->radar4d_supplement).cloud_world;
217 if (change_cur_obj_bbox) {
218 new_dir = old_dir;
219 algorithm::CalculateBBoxSizeCenter2DXY(
220 cloud, new_dir, &new_size, &new_center, minimum_edge_length);
221 } else {
222 old_dir = new_dir;
223 algorithm::CalculateBBoxSizeCenter2DXY(
224 cloud, old_dir, &old_size, &old_center, minimum_edge_length);
225 }
226 // Step 2: compute 2d iou bbox to bbox
227 Eigen::Matrix2d trans_mat;
228 trans_mat(0, 0) = (old_dir.cast<double>())(0);
229 trans_mat(0, 1) = (old_dir.cast<double>())(1);
230 trans_mat(1, 0) = -(old_dir.cast<double>())(1);
231 trans_mat(1, 1) = (old_dir.cast<double>())(0);
232 Eigen::Vector2d old_center_transformed_2d =
233 static_cast<Eigen::Matrix<double, 2, 1, 0, 2, 1>>(trans_mat *
234 old_center.head(2));
235 Eigen::Vector2d new_center_transformed_2d =
236 static_cast<Eigen::Matrix<double, 2, 1, 0, 2, 1>>(trans_mat *
237 new_center.head(2));
238 old_center(0) = old_center_transformed_2d(0);
239 old_center(1) = old_center_transformed_2d(1);
240 new_center(0) = new_center_transformed_2d(0);
241 new_center(1) = new_center_transformed_2d(1);
242 Eigen::Vector3d old_size_tmp = old_size.cast<double>();
243 Eigen::Vector3d new_size_tmp = new_size.cast<double>();
244 double iou = algorithm::CalculateIou2DXY<double>(old_center, old_size_tmp,
245 new_center, new_size_tmp);
246 // Step 4: compute dist
247 double dist = (1 - iou) * match_threshold;
248 return static_cast<float>(dist);
249}
AttributeRadarPointCloud< RadarPointD > RadarPointDCloud

◆ BboxSizeDistance()

float apollo::perception::radar4d::BboxSizeDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr new_object,
const double  time_diff 
)

Compute bbox size distance for given track & object

参数
last_objectobject for computing distance
track_predictpredicted state of track for computing distance
new_objectnew detected object for computing distance
time_difftime interval from last matching
返回
float distance

在文件 distance_collection.cc99 行定义.

102 {
103 // Compute bbox size distance for last object and new object
104 // range from 0 to 1
105
106 Eigen::Vector3f old_bbox_dir = last_object->output_direction.cast<float>();
107 Eigen::Vector3f new_bbox_dir = new_object->direction.cast<float>();
108 Eigen::Vector3f old_bbox_size = last_object->output_size.cast<float>();
109 Eigen::Vector3f new_bbox_size = new_object->size.cast<float>();
110
111 float size_dist = 0.0f;
112 double dot_val_00 = fabs(old_bbox_dir(0) * new_bbox_dir(0) +
113 old_bbox_dir(1) * new_bbox_dir(1));
114 double dot_val_01 = fabs(old_bbox_dir(0) * new_bbox_dir(1) -
115 old_bbox_dir(1) * new_bbox_dir(0));
116 float temp_val_0 = 0.0f;
117 float temp_val_1 = 0.0f;
118 if (dot_val_00 > dot_val_01) {
119 temp_val_0 = static_cast<float>(fabs(old_bbox_size(0) - new_bbox_size(0))) /
120 std::max(old_bbox_size(0), new_bbox_size(0));
121 temp_val_1 = static_cast<float>(fabs(old_bbox_size(1) - new_bbox_size(1))) /
122 std::max(old_bbox_size(1), new_bbox_size(1));
123 size_dist = std::min(temp_val_0, temp_val_1);
124 } else {
125 temp_val_0 = static_cast<float>(fabs(old_bbox_size(0) - new_bbox_size(1))) /
126 std::max(old_bbox_size(0), new_bbox_size(1));
127 temp_val_1 = static_cast<float>(fabs(old_bbox_size(1) - new_bbox_size(0))) /
128 std::max(old_bbox_size(1), new_bbox_size(0));
129 size_dist = std::min(temp_val_0, temp_val_1);
130 }
131
132 return size_dist;
133}

◆ CentroidShiftDistance()

float apollo::perception::radar4d::CentroidShiftDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr cur_obj,
const double  time_diff 
)

Compute centroid shift distance for object and background match

参数
last_objectobject for computing distance
track_predictunused
cur_objnew detected object for computing distance
time_diffunused
返回
float distance

在文件 distance_collection.cc180 行定义.

183 {
184 float dist = static_cast<float>(
185 (last_object->barycenter.head(2) - new_object->barycenter.head(2))
186 .norm());
187 return dist;
188}

◆ ComputeObjectShapeFromPolygon() [1/2]

void apollo::perception::radar4d::ComputeObjectShapeFromPolygon ( std::shared_ptr< base::Object object,
bool  use_world_cloud = false 
)

◆ ComputeObjectShapeFromPolygon() [2/2]

void apollo::perception::radar4d::ComputeObjectShapeFromPolygon ( std::shared_ptr< Object object,
bool  use_world_cloud 
)

在文件 radar_object_util.cc63 行定义.

64 {
65 const PointCloud<PointD>& polygon = object->polygon;
66 const RadarPointCloud<RadarPointF>& cloud =
67 object->radar4d_supplement.cloud;
68 const RadarPointCloud<RadarPointD>& world_cloud =
69 object->radar4d_supplement.cloud_world;
70
71 if (polygon.empty() || cloud.empty()) {
72 AINFO << "Failed to compute box, polygon size: " << polygon.size()
73 << " cloud size: " << cloud.size();
74 return;
75 }
76
77 // note here we assume direction is not changed
78 Eigen::Vector2d polygon_xy;
79 Eigen::Vector2d projected_polygon_xy;
80 Eigen::Vector3d raw_direction = object->direction.cast<double>();
81 Eigen::Vector2d direction = raw_direction.head<2>();
82 Eigen::Vector2d odirection(-direction(1), direction(0));
83
84 constexpr double kDoubleMax = std::numeric_limits<double>::max();
85 Eigen::Vector2d min_polygon_xy(kDoubleMax, kDoubleMax);
86 Eigen::Vector2d max_polygon_xy(-kDoubleMax, -kDoubleMax);
87
88 // note we keep this offset to avoid numeric precision issues in world frame
89 Eigen::Vector2d offset(object->polygon[0].x, object->polygon[0].y);
90
91 for (const auto& point : object->polygon.points()) {
92 polygon_xy << point.x, point.y;
93 polygon_xy -= offset;
94 projected_polygon_xy(0) = direction.dot(polygon_xy);
95 projected_polygon_xy(1) = odirection.dot(polygon_xy);
96 min_polygon_xy(0) = std::min(min_polygon_xy(0), projected_polygon_xy(0));
97 min_polygon_xy(1) = std::min(min_polygon_xy(1), projected_polygon_xy(1));
98 max_polygon_xy(0) = std::max(max_polygon_xy(0), projected_polygon_xy(0));
99 max_polygon_xy(1) = std::max(max_polygon_xy(1), projected_polygon_xy(1));
100 }
101
102 double min_z = 0.0;
103 double max_z = 0.0;
104 if (use_world_cloud) {
105 min_z = world_cloud[0].z;
106 max_z = world_cloud[0].z;
107 for (const auto& point : world_cloud.points()) {
108 min_z = std::min(min_z, point.z);
109 max_z = std::max(max_z, point.z);
110 }
111 } else {
112 min_z = cloud[0].z;
113 max_z = cloud[0].z;
114 for (const auto& point : cloud.points()) {
115 min_z = std::min(min_z, static_cast<double>(point.z));
116 max_z = std::max(max_z, static_cast<double>(point.z));
117 }
118 }
119
120 // update size
121 object->size << static_cast<float>(max_polygon_xy(0) - min_polygon_xy(0)),
122 static_cast<float>(max_polygon_xy(1) - min_polygon_xy(1)),
123 static_cast<float>(max_z - min_z);
124 // for safety issues, set a default minmium value
125 object->size(0) = std::max(object->size(0), 0.01f);
126 object->size(1) = std::max(object->size(1), 0.01f);
127 object->size(2) = std::max(object->size(2), 0.01f);
128 // update center
129 projected_polygon_xy << (min_polygon_xy(0) + max_polygon_xy(0)) * 0.5,
130 (min_polygon_xy(1) + max_polygon_xy(1)) * 0.5;
131 polygon_xy = projected_polygon_xy(0) * direction +
132 projected_polygon_xy(1) * odirection;
133 object->center << polygon_xy(0) + offset(0), polygon_xy(1) + offset(1), min_z;
134}

◆ convertPoseToLoc()

void apollo::perception::radar4d::convertPoseToLoc ( const Eigen::Affine3d &  pose,
localization::LocalizationEstimate localization 
)

在文件 mrf_engine.cc190 行定义.

191 {
192 ADEBUG << "translation x y z " << pose.translation()[0] << " "
193 << pose.translation()[1] << " " << pose.translation()[2];
194 localization->mutable_pose()->mutable_position()->set_x(
195 pose.translation()[0]);
196 localization->mutable_pose()->mutable_position()->set_y(
197 pose.translation()[1]);
198 localization->mutable_pose()->mutable_position()->set_z(
199 pose.translation()[2]);
200 Eigen::Quaterniond p(pose.rotation());
201 localization->mutable_pose()->mutable_orientation()->set_qx(p.x());
202 localization->mutable_pose()->mutable_orientation()->set_qy(p.y());
203 localization->mutable_pose()->mutable_orientation()->set_qz(p.z());
204 localization->mutable_pose()->mutable_orientation()->set_qw(p.w());
205}
#define ADEBUG
Definition log.h:41

◆ CYBER_REGISTER_COMPONENT()

apollo::perception::radar4d::CYBER_REGISTER_COMPONENT ( Radar4dDetectionComponent  )

◆ DirectionDistance()

float apollo::perception::radar4d::DirectionDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr new_object,
const double  time_diff 
)

Compute direction distance for given track & object

参数
last_objectobject for computing distance
track_predictpredicted state of track for computing distance
new_objectnew detected object for computing distance
time_difftime interval from last matching
返回
float distance

在文件 distance_collection.cc70 行定义.

73 {
74 // Compute direction distance for last object and new object
75 // range from 0 to 2
76
77 Eigen::Vector3f old_anchor_point =
78 (last_object->belief_anchor_point).cast<float>();
79 Eigen::Vector3f new_anchor_point = (new_object->anchor_point).cast<float>();
80 Eigen::Vector3f anchor_point_shift_dir = new_anchor_point - old_anchor_point;
81 anchor_point_shift_dir[2] = 0.0;
82
83 Eigen::Vector3f track_motion_dir = track_predict.head(6).tail(3);
84 track_motion_dir[2] = 0.0;
85
86 double cos_theta = 0.994; // average cos
87 if (!track_motion_dir.head(2).isZero() &&
88 !anchor_point_shift_dir.head(2).isZero()) {
89 // cos_theta = vector_cos_theta_2d_xy(track_motion_dir,
90 // anchor_point_shift_dir);
91 cos_theta = algorithm::CalculateCosTheta2DXY<float>(track_motion_dir,
92 anchor_point_shift_dir);
93 }
94 float direction_dist = static_cast<float>(-cos_theta) + 1.0f;
95
96 return direction_dist;
97}

◆ GetBoundingBox2d() [1/2]

void apollo::perception::radar4d::GetBoundingBox2d ( const std::shared_ptr< base::Object > &  object,
base::RadarPointCloud< base::RadarPointD > *  box,
double  expand = 0.0 
)

◆ GetBoundingBox2d() [2/2]

void apollo::perception::radar4d::GetBoundingBox2d ( const std::shared_ptr< Object > &  object,
RadarPointCloud< RadarPointD > *  box,
double  expand 
)

在文件 radar_object_util.cc35 行定义.

36 {
37 box->clear();
38 box->resize(4);
39
40 Eigen::Vector3d direction = object->direction.cast<double>();
41 Eigen::Vector3d odirection(-direction(1), direction(0), 0.0);
42 double half_length = object->size(0) * 0.5 + expand;
43 double half_width = object->size(1) * 0.5 + expand;
44
45 box->at(0).x = half_length * direction(0) + half_width * odirection(0) +
46 object->center(0);
47 box->at(0).y = half_length * direction(1) + half_width * odirection(1) +
48 object->center(1);
49 box->at(1).x = -half_length * direction(0) + half_width * odirection(0) +
50 object->center(0);
51 box->at(1).y = -half_length * direction(1) + half_width * odirection(1) +
52 object->center(1);
53 box->at(2).x = -half_length * direction(0) - half_width * odirection(0) +
54 object->center(0);
55 box->at(2).y = -half_length * direction(1) - half_width * odirection(1) +
56 object->center(1);
57 box->at(3).x = half_length * direction(0) - half_width * odirection(0) +
58 object->center(0);
59 box->at(3).y = half_length * direction(1) - half_width * odirection(1) +
60 object->center(1);
61}
const RadarPointT * at(size_t col, size_t row) const

◆ GPUAssert()

void apollo::perception::radar4d::GPUAssert ( cudaError_t  code,
const char *  file,
int  line,
bool  abort = true 
)
inline

在文件 common.h61 行定义.

62 {
63 if (code != cudaSuccess) {
64 fprintf(stderr, "GPUassert: %s %s %d\n", cudaGetErrorString(code), file,
65 line);
66 if (abort) exit(code);
67 }
68}

◆ HistogramDistance()

float apollo::perception::radar4d::HistogramDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr new_object,
const double  time_diff 
)

Compute histogram distance for given track & object

参数
last_objectobject for computing distance
track_predictpredicted state of track for computing distance
new_objectnew detected object for computing distance
time_difftime interval from last matching
返回
float distance

在文件 distance_collection.cc154 行定义.

157 {
158 // Compute histogram distance for last object and new object
159 // range from 0 to 3
160
161 const std::vector<float>& old_object_shape_features =
162 last_object->shape_features;
163 const std::vector<float>& new_object_shape_features =
164 new_object->shape_features;
165
166 if (old_object_shape_features.size() != new_object_shape_features.size()) {
167 AINFO << "sizes of compared features not matched. TrackObjectDistance";
168 return 100;
169 }
170
171 float histogram_dist = 0.0f;
172 for (size_t i = 0; i < old_object_shape_features.size(); ++i) {
173 histogram_dist +=
174 std::fabs(old_object_shape_features[i] - new_object_shape_features[i]);
175 }
176
177 return histogram_dist;
178}

◆ LocationDistance()

float apollo::perception::radar4d::LocationDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr new_object,
const double  time_diff 
)

Compute location distance for given track & object

参数
last_objectobject for computing distance
track_predictpredicted state of track for computing distance
new_objectnew detected object for computing distance
time_difftime interval from last matching
返回
float distance

在文件 distance_collection.cc31 行定义.

34 {
35 // Compute locatin distance for last object and new object
36 // range from 0 to positive infinity
37
38 Eigen::Vector3f measured_anchor_point =
39 (new_object->anchor_point).cast<float>();
40 Eigen::Vector3f predicted_anchor_point = track_predict.head(3);
41 Eigen::Vector3f measure_predict_diff =
42 measured_anchor_point - predicted_anchor_point;
43
44 float location_dist = static_cast<float>(sqrt(
45 (measure_predict_diff.head(2).cwiseProduct(measure_predict_diff.head(2)))
46 .sum()));
47
48 /* NEED TO NOTICE: All the states would be collected mainly based on
49 * states of tracked objects. Thus, update tracked object when you
50 * update the state of track !!!!! */
51 Eigen::Vector2d ref_dir = last_object->output_velocity.head(2);
52 double speed = ref_dir.norm();
53 ref_dir /= speed;
54
55 /* Let location distance generated from a normal distribution with
56 * symmetric variance. Modify its variance when speed greater than
57 * a threshold. Penalize variance other than motion direction. */
58 if (speed > 2) {
59 Eigen::Vector2d ref_o_dir = Eigen::Vector2d(ref_dir[1], -ref_dir[0]);
60 double dx = ref_dir(0) * measure_predict_diff(0) +
61 ref_dir(1) * measure_predict_diff(1);
62 double dy = ref_o_dir(0) * measure_predict_diff(0) +
63 ref_o_dir(1) * measure_predict_diff(1);
64 location_dist = static_cast<float>(sqrt(dx * dx * 0.5 + dy * dy * 2));
65 }
66
67 return location_dist;
68}

◆ MeasureAnchorPointVelocity()

void apollo::perception::radar4d::MeasureAnchorPointVelocity ( TrackedObjectPtr  new_object,
const TrackedObjectConstPtr old_object,
const double &  time_diff 
)

Measure anchor point velocity

参数
new_objectfor current updating
old_objectfor last updating
time_difftime interval from last updating

在文件 measurement_collection.cc26 行定义.

28 {
29 // Compute 2D anchor point velocity measurement
30 Eigen::Vector3d measured_anchor_point_velocity =
31 new_object->anchor_point - old_object->belief_anchor_point;
32 measured_anchor_point_velocity /= time_diff;
33 measured_anchor_point_velocity(2) = 0.0;
34 new_object->measured_barycenter_velocity = measured_anchor_point_velocity;
35}

◆ MeasureBboxCenterVelocity()

void apollo::perception::radar4d::MeasureBboxCenterVelocity ( TrackedObjectPtr  new_object,
const TrackedObjectConstPtr old_object,
const double &  time_diff 
)

Measure bbox center velocity

参数
new_objectfor current updating
old_objectfor last updating
time_difftime interval from last updating

在文件 measurement_collection.cc37 行定义.

39 {
40 // Compute 2D bbox center velocity measurement
41 Eigen::Vector3f old_dir_tmp = old_object->output_direction.cast<float>();
42 // Eigen::Vector3d old_size = old_object->output_size;
43 Eigen::Vector3d old_center = old_object->output_center;
44 Eigen::Vector3f new_size_tmp;
45 Eigen::Vector3d new_center;
46 float minimum_edge_length = 0.01f;
48 (new_object->object_ptr->radar4d_supplement).cloud_world;
49 algorithm::CalculateBBoxSizeCenter2DXY(cloud, old_dir_tmp, &new_size_tmp,
50 &new_center, minimum_edge_length);
51 // Eigen::Vector3d old_dir = old_dir_tmp.cast<double>();
52 // Eigen::Vector3d new_size = new_size_tmp.cast<double>();
53 Eigen::Vector3d measured_bbox_center_velocity_with_old_dir =
54 (new_center - old_center);
55 measured_bbox_center_velocity_with_old_dir /= time_diff;
56 measured_bbox_center_velocity_with_old_dir(2) = 0.0;
57 Eigen::Vector3d measured_bbox_center_velocity =
58 measured_bbox_center_velocity_with_old_dir;
59 Eigen::Vector3d project_dir =
60 new_object->anchor_point - old_object->belief_anchor_point;
61 if (measured_bbox_center_velocity.dot(project_dir) <= 0) {
62 measured_bbox_center_velocity = Eigen::Vector3d::Zero();
63 }
64 new_object->measured_center_velocity = measured_bbox_center_velocity;
65}

◆ MeasureBboxCornerVelocity()

void apollo::perception::radar4d::MeasureBboxCornerVelocity ( TrackedObjectPtr  new_object,
const TrackedObjectConstPtr old_object,
const double &  time_diff 
)

Measure bbox corner velocity

参数
new_objectfor current updating
old_objectfor last updating
time_difftime interval from last updating

在文件 measurement_collection.cc67 行定义.

69 {
70 // Compute 2D bbxo corner velocity measurement
71 Eigen::Vector3f old_dir_tmp = old_object->output_direction.cast<float>();
72 Eigen::Vector3d old_size = old_object->output_size;
73 Eigen::Vector3d old_center = old_object->output_center;
74 Eigen::Vector3f new_size_tmp;
75 Eigen::Vector3d new_center;
76 float minimum_edge_length = 0.01f;
78 (new_object->object_ptr->radar4d_supplement).cloud_world;
79 algorithm::CalculateBBoxSizeCenter2DXY(cloud, old_dir_tmp, &new_size_tmp,
80 &new_center, minimum_edge_length);
81 Eigen::Vector3d old_dir = old_dir_tmp.cast<double>();
82 Eigen::Vector3d new_size = new_size_tmp.cast<double>();
83 Eigen::Vector3d ortho_old_dir(-old_dir(1), old_dir(0), 0.0);
84 Eigen::Vector3d old_bbox_corner_list[4];
85 Eigen::Vector3d new_bbox_corner_list[4];
86 Eigen::Vector3d old_bbox_corner = old_center + old_dir * old_size(0) * 0.5 +
87 ortho_old_dir * old_size(1) * 0.5;
88 Eigen::Vector3d new_bbox_corner = new_center + old_dir * new_size(0) * 0.5 +
89 ortho_old_dir * new_size(1) * 0.5;
90 old_bbox_corner_list[0] = old_bbox_corner;
91 new_bbox_corner_list[0] = new_bbox_corner;
92 old_bbox_corner = old_center - old_dir * old_size(0) * 0.5 +
93 ortho_old_dir * old_size(1) * 0.5;
94 new_bbox_corner = new_center - old_dir * new_size(0) * 0.5 +
95 ortho_old_dir * new_size(1) * 0.5;
96 old_bbox_corner_list[1] = old_bbox_corner;
97 new_bbox_corner_list[1] = new_bbox_corner;
98 old_bbox_corner = old_center + old_dir * old_size(0) * 0.5 -
99 ortho_old_dir * old_size(1) * 0.5;
100 new_bbox_corner = new_center + old_dir * new_size(0) * 0.5 -
101 ortho_old_dir * new_size(1) * 0.5;
102 old_bbox_corner_list[2] = old_bbox_corner;
103 new_bbox_corner_list[2] = new_bbox_corner;
104 old_bbox_corner = old_center - old_dir * old_size(0) * 0.5 -
105 ortho_old_dir * old_size(1) * 0.5;
106 new_bbox_corner = new_center - old_dir * new_size(0) * 0.5 -
107 ortho_old_dir * new_size(1) * 0.5;
108 old_bbox_corner_list[3] = old_bbox_corner;
109 new_bbox_corner_list[3] = new_bbox_corner;
110
111 // calculate the nearest corner
112 Eigen::Vector3d ref_location = new_object->sensor_to_local_pose.translation();
113 Eigen::Vector3d nearest_old_bbox_corner = old_bbox_corner_list[0];
114 Eigen::Vector3d nearest_new_bbox_corner = new_bbox_corner_list[0];
115 double min_center_distance = (ref_location - nearest_new_bbox_corner).norm();
116 for (size_t i = 1; i < 4; ++i) {
117 double center_distance = (ref_location - new_bbox_corner_list[i]).norm();
118 if (center_distance < min_center_distance) {
119 min_center_distance = center_distance;
120 nearest_old_bbox_corner = old_bbox_corner_list[i];
121 nearest_new_bbox_corner = new_bbox_corner_list[i];
122 }
123 }
124 // no projection
125 new_object->measured_nearest_corner_velocity =
126 (nearest_new_bbox_corner - nearest_old_bbox_corner) / time_diff;
127
128 // select project_dir by change of size
129 Eigen::Vector3d direct_old_size = old_object->size;
130 Eigen::Vector3d direct_new_size = new_object->size;
131 double length_change =
132 fabs(direct_old_size(0) - direct_new_size(0)) / direct_old_size(0);
133 double width_change =
134 fabs(direct_old_size(1) - direct_new_size(1)) / direct_old_size(1);
135
136 const double max_change_thresh = 0.1;
137 Eigen::Vector3d project_dir;
138 if (length_change < max_change_thresh && width_change < max_change_thresh) {
139 project_dir = new_object->center - old_object->center;
140 } else {
141 project_dir = new_object->anchor_point - old_object->belief_anchor_point;
142 }
143
144 for (size_t i = 0; i < 4; ++i) {
145 old_bbox_corner = old_bbox_corner_list[i];
146 new_bbox_corner = new_bbox_corner_list[i];
147 new_object->corners[i] = new_bbox_corner_list[i];
148 Eigen::Vector3d bbox_corner_velocity =
149 ((new_bbox_corner - old_bbox_corner) / time_diff);
150 Eigen::Vector3d bbox_corner_velocity_on_project_dir =
151 algorithm::Calculate2DXYProjectVector<double>(bbox_corner_velocity,
152 project_dir);
153 // set velocity as 0 when conflict
154 if (bbox_corner_velocity_on_project_dir.dot(project_dir) <= 0) {
155 bbox_corner_velocity_on_project_dir = Eigen::Vector3d::Zero();
156 }
157 new_object->measured_corners_velocity[i] =
158 bbox_corner_velocity_on_project_dir;
159 }
160}

◆ operator<()

bool apollo::perception::radar4d::operator< ( const MatchCost m1,
const MatchCost m2 
)

在文件 gnn_bipartite_graph_matcher.cc37 行定义.

37 {
38 return m1.cost_ < m2.cost_;
39}

◆ operator<<()

std::ostream & apollo::perception::radar4d::operator<< ( std::ostream &  os,
const MatchCost m 
)

在文件 gnn_bipartite_graph_matcher.cc41 行定义.

41 {
42 os << "MatchCost ridx:" << m.RowIdx() << " cidx:" << m.ColIdx()
43 << " Cost:" << m.Cost();
44 return os;
45}

◆ PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER() [1/2]

apollo::perception::radar4d::PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER ( GnnBipartiteGraphMatcher  )

◆ PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER() [2/2]

apollo::perception::radar4d::PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER ( MultiHmBipartiteGraphMatcher  )

◆ PERCEPTION_REGISTER_CLASSIFIER()

apollo::perception::radar4d::PERCEPTION_REGISTER_CLASSIFIER ( FusedClassifier  )

◆ PERCEPTION_REGISTER_DETECTOR()

apollo::perception::radar4d::PERCEPTION_REGISTER_DETECTOR ( Radar4dDetection  )

◆ PERCEPTION_REGISTER_MRFFILTER() [1/2]

apollo::perception::radar4d::PERCEPTION_REGISTER_MRFFILTER ( MrfMotionFilter  )

◆ PERCEPTION_REGISTER_MRFFILTER() [2/2]

apollo::perception::radar4d::PERCEPTION_REGISTER_MRFFILTER ( MrfShapeFilter  )

◆ PERCEPTION_REGISTER_MULTITARGET_TRACKER()

apollo::perception::radar4d::PERCEPTION_REGISTER_MULTITARGET_TRACKER ( MrfEngine  )

◆ PERCEPTION_REGISTER_ONESHOTTYPEFUSION()

apollo::perception::radar4d::PERCEPTION_REGISTER_ONESHOTTYPEFUSION ( CCRFOneShotTypeFusion  )

◆ PERCEPTION_REGISTER_PREPROCESSOR()

apollo::perception::radar4d::PERCEPTION_REGISTER_PREPROCESSOR ( RadarPreprocessor  )

◆ PERCEPTION_REGISTER_RADAR_OBSTACLE_PERCEPTION()

apollo::perception::radar4d::PERCEPTION_REGISTER_RADAR_OBSTACLE_PERCEPTION ( RadarObstaclePerception  )

◆ PERCEPTION_REGISTER_REGISTERER() [1/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseBipartiteGraphMatcher  )

◆ PERCEPTION_REGISTER_REGISTERER() [2/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseClassifier  )

◆ PERCEPTION_REGISTER_REGISTERER() [3/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseDetector  )

◆ PERCEPTION_REGISTER_REGISTERER() [4/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseMultiTargetTracker  )

◆ PERCEPTION_REGISTER_REGISTERER() [5/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseOneShotTypeFusion  )

◆ PERCEPTION_REGISTER_REGISTERER() [6/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BasePreprocessor  )

◆ PERCEPTION_REGISTER_REGISTERER() [7/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseRadarObstaclePerception  )

◆ PERCEPTION_REGISTER_REGISTERER() [8/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseRoiFilter  )

◆ PERCEPTION_REGISTER_REGISTERER() [9/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( BaseSequenceTypeFusion  )

◆ PERCEPTION_REGISTER_REGISTERER() [10/10]

apollo::perception::radar4d::PERCEPTION_REGISTER_REGISTERER ( MrfBaseFilter  )

◆ PERCEPTION_REGISTER_ROI_FILTER()

apollo::perception::radar4d::PERCEPTION_REGISTER_ROI_FILTER ( HdmapRadarRoiFilter  )

◆ PERCEPTION_REGISTER_SEQUENCETYPEFUSION()

apollo::perception::radar4d::PERCEPTION_REGISTER_SEQUENCETYPEFUSION ( CCRFSequenceTypeFusion  )

◆ PointNumDistance()

float apollo::perception::radar4d::PointNumDistance ( const TrackedObjectConstPtr last_object,
const Eigen::VectorXf &  track_predict,
const TrackedObjectConstPtr new_object,
const double  time_diff 
)

Compute point num distance for given track & object

参数
last_objectobject for computing distance
track_predictpredicted state of track for computing distance
new_objectnew detected object for computing distance
time_difftime interval from last matching
返回
float distance

在文件 distance_collection.cc135 行定义.

138 {
139 // Compute point num distance for last object and new object
140 // range from 0 and 1
141
142 int old_point_number = static_cast<int>(
143 (last_object->object_ptr->radar4d_supplement).cloud_world.size());
144 int new_point_number = static_cast<int>(
145 (new_object->object_ptr->radar4d_supplement).cloud_world.size());
146
147 float point_num_dist =
148 static_cast<float>(fabs(old_point_number - new_point_number)) * 1.0f /
149 static_cast<float>(std::max(old_point_number, new_point_number));
150
151 return point_num_dist;
152}

◆ RemoveStaleDataFromMap()

void apollo::perception::radar4d::RemoveStaleDataFromMap ( double  timestamp,
std::map< double, TrackedObjectPtr > *  data 
)

在文件 mrf_track_data.cc180 行定义.

181 {
182 auto iter = data->begin();
183 while (iter != data->end()) {
184 if (iter->first < timestamp) {
185 data->erase(iter++);
186 } else {
187 break;
188 }
189 }
190}

变量说明

◆ EIGEN_ALIGN16

struct apollo::perception::radar4d::TrackedObject apollo::perception::radar4d::EIGEN_ALIGN16