Apollo 10.0
自动驾驶开放平台
|
命名空间 | |
namespace | centerpoint |
namespace | cnnseg |
namespace | maskpillars |
namespace | pointpillars |
namespace | type_util |
namespace | util |
函数 | |
__attribute__ ((constructor)) void LidarFramePoolInitialize() | |
void | GetBoundingBox2d (const std::shared_ptr< Object > &object, PointCloud< PointD > *box, double expand) |
void | ComputeObjectShapeFromPolygon (std::shared_ptr< Object > object, bool use_world_cloud) |
void | ComputePolygonDirection (const Eigen::Vector3d &ref_center, const base::ObjectPtr &object, Eigen::Vector3f *direction) |
Compute polygon direction | |
void | ComputeMinMaxDirectionPoint (const base::ObjectPtr &object, const Eigen::Vector3d &ref_center, size_t *max_point_index, size_t *min_point_index) |
Compute min max direction | |
void | GetBoundingBox2d (const std::shared_ptr< base::Object > &object, base::PointCloud< base::PointD > *box, double expand=0.0) |
Get the Bounding Box vertices and save in polygon type | |
void | ComputeObjectShapeFromPolygon (std::shared_ptr< base::Object > object, bool use_world_cloud=false) |
compute object shape(center, size) from given direction and polygon | |
void | SetSemanticLabel (PointSemanticLabel label, uint8_t *value) |
PointSemanticLabel | GetSemanticLabel (uint8_t value) |
bool | IsSemanticLabelEqual (PointSemanticLabel label, uint8_t value) |
void | SetMotionLabel (PointMotionLabel label, uint8_t *value) |
PointMotionLabel | GetMotionLabel (uint8_t value) |
bool | IsMotionLabelEqual (PointMotionLabel label, uint8_t value) |
bool | LoadPCLPCD (const std::string &file_path, base::PointFCloud *cloud_out) |
bool | WritePcdByLabel (const std::string &file_path, const base::PointFCloud &cloud, const LidarPointLabel &label) |
template<typename PointT > | |
void | TransformToPCLXYZI (const base::AttributePointCloud< PointT > &org_cloud, const pcl::PointCloud< pcl::PointXYZI >::Ptr &out_cloud_ptr) |
void | TransformFromPCLXYZI (const pcl::PointCloud< pcl::PointXYZI >::Ptr &org_cloud_ptr, const base::PointFCloudPtr &out_cloud_ptr) |
void | DownSampleCloudByVoxelGrid (const pcl::PointCloud< pcl::PointXYZI >::Ptr &cloud_ptr, const pcl::PointCloud< pcl::PointXYZI >::Ptr &filtered_cloud_ptr, float lx=0.01f, float ly=0.01f, float lz=0.01f) |
template<typename PointT > | |
void | DownSampleCloudByVoxelGrid (const typename pcl::PointCloud< PointT >::Ptr &input_cloud_ptr, typename pcl::PointCloud< PointT >::Ptr output_cloud_ptr, float lx=0.01f, float ly=0.01f, float lz=0.01f) |
template<typename PointT > | |
void | FilterPointsOutsideRange (const typename pcl::PointCloud< PointT >::Ptr &input_cloud_ptr, const std::string &filter_axis, const double &limit_min, const double &limit_max, typename pcl::PointCloud< PointT >::Ptr output_cloud_ptr) |
template<typename PointT > | |
void | LoadPointCloud (const std::string &filename, typename pcl::PointCloud< PointT >::Ptr point_cloud) |
template<typename PointT > | |
void | DownSamplePointCloud (const typename pcl::PointCloud< PointT >::Ptr &intput_cloud_ptr, typename pcl::PointCloud< PointT >::Ptr out_cloud_ptr, int num_points) |
uint32_t | GetIndex (uint32_t r, uint32_t c, uint32_t cols) |
PERCEPTION_REGISTER_SCENESERVICECONTENT (GroundServiceContent) | |
PERCEPTION_REGISTER_SCENESERVICE (GroundService) | |
PERCEPTION_REGISTER_SCENESERVICECONTENT (ROIServiceContent) | |
PERCEPTION_REGISTER_SCENESERVICE (ROIService) | |
PERCEPTION_REGISTER_REGISTERER (SceneServiceContent) | |
PERCEPTION_REGISTER_REGISTERER (SceneService) | |
float | get_3Dbox_iou_len (float center1, float len1, float center2, float len2) |
float | get_3dbox_iou (base::ObjectPtr obj1, base::ObjectPtr obj2) |
PERCEPTION_REGISTER_LIDARDETECTOR (CenterPointDetection) | |
PERCEPTION_REGISTER_LIDARDETECTOR (CNNSegmentation) | |
template<class T > | |
void | DisjointSetMakeSet (T *x) |
template<class T > | |
T * | DisjointSetFindRecursive (T *x) |
template<class T > | |
T * | DisjointSetFindLoop (T *x) |
template<class T > | |
T * | DisjointSetFind (T *x) |
template<class T > | |
void | DisjointSetMerge (T *x, const T *y) |
template<class T > | |
void | DisjointSetUnion (T *x, T *y) |
int | F2I (float val, float ori, float scale) |
void | GroupPc2Pixel (float pc_x, float pc_y, float scale, float range, int *x, int *y) |
int | Pc2Pixel (float in_pc, float in_range, float out_size) |
float | Pixel2Pc (int in_pixel, float in_size, float out_range) |
PERCEPTION_REGISTER_LIDARDETECTOR (MaskPillarsDetection) | |
void | GPUAssert (cudaError_t code, const char *file, int line, bool abort=true) |
PERCEPTION_REGISTER_LIDARDETECTOR (PointPillarsDetection) | |
PERCEPTION_REGISTER_REGISTERER (BaseLidarDetector) | |
CYBER_REGISTER_COMPONENT (LidarDetectionComponent) | |
CYBER_REGISTER_COMPONENT (LidarDetectionFilterComponent) | |
CYBER_REGISTER_COMPONENT (LidarOutputComponent) | |
PERCEPTION_REGISTER_ONESHOTTYPEFUSION (CCRFOneShotTypeFusion) | |
PERCEPTION_REGISTER_SEQUENCETYPEFUSION (CCRFSequenceTypeFusion) | |
PERCEPTION_REGISTER_CLASSIFIER (FusedClassifier) | |
PERCEPTION_REGISTER_REGISTERER (BaseOneShotTypeFusion) | |
PERCEPTION_REGISTER_REGISTERER (BaseSequenceTypeFusion) | |
PERCEPTION_REGISTER_REGISTERER (BaseBipartiteGraphMatcher) | |
PERCEPTION_REGISTER_REGISTERER (BaseClassifier) | |
PERCEPTION_REGISTER_REGISTERER (BaseMultiTargetTracker) | |
CYBER_REGISTER_COMPONENT (LidarTrackingComponent) | |
float | EuclideanDistance (const TrackedObjectConstPtr &last_object, const Eigen::VectorXf &track_predict, const TrackedObjectConstPtr &new_object, const double time_diff) |
: compute euclidean distance for given track & object | |
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 | MeasureBboxCenterHistoryVelocity (const MlfTrackDataConstPtr &track_data, TrackedObjectPtr new_object) |
void | MeasureBboxCornerVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff) |
Measure bbox corner velocity | |
void | MeasureBboxCornerHistoryVelocity (const MlfTrackDataConstPtr &track_data, TrackedObjectPtr new_object) |
void | ComputeBboxCornerHistoryVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff, TrackedObjectPtr curr_object) |
void | MeasureObjectDetectionVelocity (TrackedObjectPtr new_object, const TrackedObjectConstPtr &old_object, const double &time_diff) |
Measure object-detection center and corner velocity | |
void | MeasureObjectDetectionHistoryVelocity (const MlfTrackDataConstPtr &track_data, TrackedObjectPtr new_object) |
PERCEPTION_REGISTER_REGISTERER (MlfBaseFilter) | |
PERCEPTION_REGISTER_MULTITARGET_TRACKER (MlfEngine) | |
PERCEPTION_REGISTER_MLFFILTER (MlfMotionFilter) | |
PERCEPTION_REGISTER_MLFFILTER (MlfShapeFilter) | |
PERCEPTION_REGISTER_MLFFILTER (MlfTypeFilter) | |
bool | JudgeBlindTrafficCone (const MlfTrackDataConstPtr &track_data, double frame_timestamp, const Eigen::Vector3d &local_to_global_offset, Eigen::Affine3d &lidar2world_pose, Eigen::Affine3d &lidar2novatel_pose) |
PERCEPTION_REGISTER_ONESHOTTYPEFUSION (CCRFSingleShotTypeFusion) | |
PERCEPTION_REGISTER_SEQUENCETYPEFUSION (CCRFMultiShotTypeFusion) | |
PERCEPTION_REGISTER_REGISTERER (BaseSingleShotTypeFusion) | |
PERCEPTION_REGISTER_REGISTERER (BaseMultiShotTypeFusion) | |
PERCEPTION_REGISTER_GROUNDDETECTOR (GroundServiceDetector) | |
PERCEPTION_REGISTER_GROUNDDETECTOR (SpatioTemporalGroundDetector) | |
PERCEPTION_REGISTER_REGISTERER (BaseGroundDetector) | |
CYBER_REGISTER_COMPONENT (PointCloudGroundDetectComponent) | |
CYBER_REGISTER_COMPONENT (PointCloudMapROIComponent) | |
template<typename T > | |
bool | DrawPolygonMask (const typename PolygonScanCvter< T >::Polygon &polygon, Bitmap2D *bitmap, const double extend_dist=0.0, const bool no_edge_table=false) |
template<typename T > | |
bool | DrawPolygonsMask (const std::vector< typename PolygonScanCvter< T >::Polygon > &polygons, Bitmap2D *bitmap, const double extend_dist=0.0, const bool no_edge_table=false) |
PERCEPTION_REGISTER_REGISTERER (BasePointCloudPreprocessor) | |
CYBER_REGISTER_COMPONENT (PointCloudPreprocessComponent) | |
PERCEPTION_REGISTER_POINTCLOUDPREPROCESSOR (PointCloudPreprocessor) | |
变量 | |
struct apollo::perception::lidar::PCLPointXYZIT | EIGEN_ALIGN16 |
const double | kPI = 3.1415926535897932384626433832795 |
const float | STATIC_VELOCITY = 0.01 |
typedef pcl::PointXYZRGB apollo::perception::lidar::CPoint |
在文件 pcl_util.h 第 32 行定义.
typedef pcl::PointCloud<CPoint> apollo::perception::lidar::CPointCloud |
在文件 pcl_util.h 第 33 行定义.
typedef pcl::PointCloud<CPoint>::ConstPtr apollo::perception::lidar::CPointCloudConstPtr |
在文件 pcl_util.h 第 35 行定义.
typedef pcl::PointCloud<CPoint>::Ptr apollo::perception::lidar::CPointCloudPtr |
在文件 pcl_util.h 第 34 行定义.
using apollo::perception::lidar::DirectionMajor = typedef Bitmap2D::DirectionMajor |
在文件 hdmap_roi_filter.cc 第 31 行定义.
typedef std::shared_ptr<const GroundService> apollo::perception::lidar::GroundServiceConstPtr |
在文件 ground_service.h 第 110 行定义.
typedef std::shared_ptr<const GroundServiceContent> apollo::perception::lidar::GroundServiceContentConstPtr |
在文件 ground_service.h 第 107 行定义.
typedef std::shared_ptr<GroundServiceContent> apollo::perception::lidar::GroundServiceContentPtr |
在文件 ground_service.h 第 105 行定义.
typedef std::shared_ptr<GroundService> apollo::perception::lidar::GroundServicePtr |
在文件 ground_service.h 第 109 行定义.
typedef base::ConcurrentObjectPool<LidarFrame, kLidarFramePoolSize, LidarFrameInitializer> apollo::perception::lidar::LidarFramePool |
在文件 lidar_frame_pool.h 第 33 行定义.
typedef Eigen::Matrix< double, VALID_OBJECT_TYPE, VALID_OBJECT_TYPE > apollo::perception::lidar::Matrixd |
typedef std::shared_ptr<const MlfTrackData> apollo::perception::lidar::MlfTrackDataConstPtr |
在文件 mlf_track_data.h 第 183 行定义.
typedef base::ConcurrentObjectPool<MlfTrackData, kTrackDataPoolSize, MlfTrackDataInitializer> apollo::perception::lidar::MlfTrackDataPool |
在文件 track_pool_types.h 第 66 行定义.
typedef std::shared_ptr<MlfTrackData> apollo::perception::lidar::MlfTrackDataPtr |
在文件 mlf_track_data.h 第 182 行定义.
typedef std::shared_ptr< apollo::perception::base::Object > apollo::perception::lidar::ObjectPtr |
在文件 object_builder.h 第 39 行定义.
typedef apollo::perception::base::AttributePointCloud< base::PointF > apollo::perception::lidar::PointFCloud |
在文件 object_builder.h 第 40 行定义.
using apollo::perception::lidar::Polygon = typedef typename PolygonScanCvter<T>::Polygon |
在文件 hdmap_roi_filter.cc 第 36 行定义.
using apollo::perception::lidar::PolygonDType = typedef apollo::perception::base::PointCloud<PointD> |
在文件 object_builder.h 第 41 行定义.
typedef std::shared_ptr<const ROIService> apollo::perception::lidar::ROIServiceConstPtr |
在文件 roi_service.h 第 98 行定义.
typedef std::shared_ptr<const ROIServiceContent> apollo::perception::lidar::ROIServiceContentConstPtr |
在文件 roi_service.h 第 95 行定义.
typedef std::shared_ptr<ROIServiceContent> apollo::perception::lidar::ROIServiceContentPtr |
在文件 roi_service.h 第 94 行定义.
typedef std::shared_ptr<ROIService> apollo::perception::lidar::ROIServicePtr |
在文件 roi_service.h 第 97 行定义.
typedef std::shared_ptr<const SceneService> apollo::perception::lidar::SceneServiceConstPtr |
在文件 scene_service.h 第 101 行定义.
typedef std::shared_ptr<const SceneServiceContent> apollo::perception::lidar::SceneServiceContentConstPtr |
在文件 scene_service.h 第 60 行定义.
typedef std::shared_ptr<SceneServiceContent> apollo::perception::lidar::SceneServiceContentPtr |
在文件 scene_service.h 第 59 行定义.
typedef std::shared_ptr<SceneService> apollo::perception::lidar::SceneServicePtr |
在文件 scene_service.h 第 100 行定义.
typedef std::shared_ptr<const SppCluster> apollo::perception::lidar::SppClusterConstPtr |
在文件 spp_cluster.h 第 132 行定义.
typedef base::LightObjectPool<SppCluster, kSppClusterPoolSize, SppClusterInitializer, base::SensorType::VELODYNE_64> apollo::perception::lidar::SppClusterPool |
在文件 spp_pool_types.h 第 35 行定义.
typedef std::shared_ptr<SppCluster> apollo::perception::lidar::SppClusterPtr |
在文件 spp_cluster.h 第 131 行定义.
typedef std::shared_ptr<const SppLabelImage> apollo::perception::lidar::SppLabelImageConstPtr |
在文件 spp_label_image.h 第 149 行定义.
typedef std::shared_ptr<SppLabelImage> apollo::perception::lidar::SppLabelImagePtr |
在文件 spp_label_image.h 第 148 行定义.
typedef std::shared_ptr<const TrackData> apollo::perception::lidar::TrackDataConstPtr |
在文件 track_data.h 第 155 行定义.
typedef base::ConcurrentObjectPool<TrackData, kTrackDataPoolSize, TrackDataInitializer> apollo::perception::lidar::TrackDataPool |
在文件 track_pool_types.h 第 63 行定义.
typedef std::shared_ptr<TrackData> apollo::perception::lidar::TrackDataPtr |
在文件 track_data.h 第 154 行定义.
typedef std::shared_ptr<const TrackedObject> apollo::perception::lidar::TrackedObjectConstPtr |
在文件 tracked_object.h 第 221 行定义.
typedef base::ConcurrentObjectPool<TrackedObject, kTrackedObjectPoolSize, TrackedObjectInitializer> apollo::perception::lidar::TrackedObjectPool |
在文件 track_pool_types.h 第 59 行定义.
typedef std::shared_ptr<TrackedObject> apollo::perception::lidar::TrackedObjectPtr |
在文件 tracked_object.h 第 220 行定义.
typedef Eigen::Matrix< double, VALID_OBJECT_TYPE, 1 > apollo::perception::lidar::Vectord |
typedef Eigen::Matrix< int, VALID_OBJECT_TYPE, 1 > apollo::perception::lidar::Vectori |
|
strong |
枚举值 | |
---|---|
Succeed | |
InitError | |
PointCloudPreprocessorError | |
MapManagerError | |
DetectionError | |
ObjectBuilderError | |
ObjectFilterError | |
ClassifierError | |
TrackerError |
在文件 lidar_error_code.h 第 24 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
ROI | |
GROUND | |
OBJECT | |
MAX_LABEL |
在文件 lidar_point_label.h 第 22 行定义.
|
strong |
枚举值 | |
---|---|
META_UNKNOWN | |
META_SMALLMOT | |
META_BIGMOT | |
META_NONMOT | |
META_PEDESTRIAN | |
MAX_META_TYPE |
|
strong |
枚举值 | |
---|---|
STATIC | |
SKEPTICAL_MOVE | |
TRUSTED_MOVE |
在文件 track_data.h 第 29 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
MOVING | |
STATIONARY | |
MAX_LABEL |
在文件 lidar_point_label.h 第 43 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
IGNORE | |
GROUND | |
OBJECT | |
CURB | |
VEGETATION | |
FENCE | |
NOISE | |
WALL | |
MAX_LABEL |
在文件 lidar_point_label.h 第 30 行定义.
|
strong |
枚举值 | |
---|---|
OTHERS | |
SMALLMOT | |
BIGMOT | |
CYCLIST | |
PEDESTRIAN | |
CONE | |
MAX_TYPE |
在文件 spp_cluster.h 第 30 行定义.
apollo::perception::lidar::__attribute__ | ( | (constructor) | ) |
在文件 lidar_frame_pool.cc 第 25 行定义.
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | unused |
cur_obj | new detected object for computing distance |
time_diff | unused |
match_threshold | match threshold |
在文件 distance_collection.cc 第 202 行定义.
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 111 行定义.
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | unused |
cur_obj | new detected object for computing distance |
time_diff | unused |
在文件 distance_collection.cc 第 192 行定义.
void apollo::perception::lidar::ComputeBboxCornerHistoryVelocity | ( | TrackedObjectPtr | new_object, |
const TrackedObjectConstPtr & | old_object, | ||
const double & | time_diff, | ||
TrackedObjectPtr | curr_object | ||
) |
在文件 measurement_collection.cc 第 237 行定义.
void apollo::perception::lidar::ComputeMinMaxDirectionPoint | ( | const base::ObjectPtr & | object, |
const Eigen::Vector3d & | ref_center, | ||
size_t * | max_point_index, | ||
size_t * | min_point_index | ||
) |
Compute min max direction
object | new object |
ref_center | view point |
max_point_index | max point index |
min_point_index | min point index |
在文件 lidar_object_util.cc 第 216 行定义.
void apollo::perception::lidar::ComputeObjectShapeFromPolygon | ( | std::shared_ptr< base::Object > | object, |
bool | use_world_cloud = false |
||
) |
compute object shape(center, size) from given direction and polygon
object | object, center and size will be updated |
use_world_cloud | whether use world cloud or local cloud |
void apollo::perception::lidar::ComputeObjectShapeFromPolygon | ( | std::shared_ptr< Object > | object, |
bool | use_world_cloud | ||
) |
在文件 lidar_object_util.cc 第 63 行定义.
void apollo::perception::lidar::ComputePolygonDirection | ( | const Eigen::Vector3d & | ref_center, |
const base::ObjectPtr & | object, | ||
Eigen::Vector3f * | direction | ||
) |
Compute polygon direction
ref_center | view point |
object | new object |
direction | orintation |
在文件 lidar_object_util.cc 第 134 行定义.
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | LidarDetectionComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | LidarDetectionFilterComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | LidarOutputComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | LidarTrackingComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | PointCloudGroundDetectComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | PointCloudMapROIComponent | ) |
apollo::perception::lidar::CYBER_REGISTER_COMPONENT | ( | PointCloudPreprocessComponent | ) |
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 82 行定义.
T * apollo::perception::lidar::DisjointSetFind | ( | T * | x | ) |
在文件 disjoint_set.h 第 55 行定义.
T * apollo::perception::lidar::DisjointSetFindLoop | ( | T * | x | ) |
在文件 disjoint_set.h 第 37 行定义.
T * apollo::perception::lidar::DisjointSetFindRecursive | ( | T * | x | ) |
在文件 disjoint_set.h 第 29 行定义.
void apollo::perception::lidar::DisjointSetMakeSet | ( | T * | x | ) |
在文件 disjoint_set.h 第 23 行定义.
void apollo::perception::lidar::DisjointSetMerge | ( | T * | x, |
const T * | y | ||
) |
在文件 disjoint_set.h 第 67 行定义.
void apollo::perception::lidar::DisjointSetUnion | ( | T * | x, |
T * | y | ||
) |
在文件 disjoint_set.h 第 70 行定义.
|
inline |
在文件 pcl_util.h 第 128 行定义.
void apollo::perception::lidar::DownSampleCloudByVoxelGrid | ( | const typename pcl::PointCloud< PointT >::Ptr & | input_cloud_ptr, |
typename pcl::PointCloud< PointT >::Ptr | output_cloud_ptr, | ||
float | lx = 0.01f , |
||
float | ly = 0.01f , |
||
float | lz = 0.01f |
||
) |
在文件 pointcloud_util.h 第 46 行定义.
void apollo::perception::lidar::DownSamplePointCloud | ( | const typename pcl::PointCloud< PointT >::Ptr & | intput_cloud_ptr, |
typename pcl::PointCloud< PointT >::Ptr | out_cloud_ptr, | ||
int | num_points | ||
) |
在文件 pointcloud_util.h 第 81 行定义.
bool apollo::perception::lidar::DrawPolygonMask | ( | const typename PolygonScanCvter< T >::Polygon & | polygon, |
Bitmap2D * | bitmap, | ||
const double | extend_dist = 0.0 , |
||
const bool | no_edge_table = false |
||
) |
在文件 polygon_mask.h 第 43 行定义.
bool apollo::perception::lidar::DrawPolygonsMask | ( | const std::vector< typename PolygonScanCvter< T >::Polygon > & | polygons, |
Bitmap2D * | bitmap, | ||
const double | extend_dist = 0.0 , |
||
const bool | no_edge_table = false |
||
) |
在文件 polygon_mask.h 第 145 行定义.
float apollo::perception::lidar::EuclideanDistance | ( | const TrackedObjectConstPtr & | last_object, |
const Eigen::VectorXf & | track_predict, | ||
const TrackedObjectConstPtr & | new_object, | ||
const double | time_diff | ||
) |
: compute euclidean distance for given track & object
last_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 31 行定义.
|
inline |
void apollo::perception::lidar::FilterPointsOutsideRange | ( | const typename pcl::PointCloud< PointT >::Ptr & | input_cloud_ptr, |
const std::string & | filter_axis, | ||
const double & | limit_min, | ||
const double & | limit_max, | ||
typename pcl::PointCloud< PointT >::Ptr | output_cloud_ptr | ||
) |
在文件 pointcloud_util.h 第 57 行定义.
float apollo::perception::lidar::get_3dbox_iou | ( | base::ObjectPtr | obj1, |
base::ObjectPtr | obj2 | ||
) |
在文件 center_point_detection.cc 第 150 行定义.
float apollo::perception::lidar::get_3Dbox_iou_len | ( | float | center1, |
float | len1, | ||
float | center2, | ||
float | len2 | ||
) |
在文件 center_point_detection.cc 第 139 行定义.
void apollo::perception::lidar::GetBoundingBox2d | ( | const std::shared_ptr< base::Object > & | object, |
base::PointCloud< base::PointD > * | box, | ||
double | expand = 0.0 |
||
) |
Get the Bounding Box vertices and save in polygon type
object | |
box | bounding box vertices(4 in xy plane) |
expand | expand valud, in meter |
void apollo::perception::lidar::GetBoundingBox2d | ( | const std::shared_ptr< Object > & | object, |
PointCloud< PointD > * | box, | ||
double | expand | ||
) |
在文件 lidar_object_util.cc 第 35 行定义.
|
inline |
在文件 ground_service.cc 第 69 行定义.
|
inline |
在文件 lidar_point_label.h 第 70 行定义.
|
inline |
在文件 lidar_point_label.h 第 56 行定义.
|
inline |
|
inline |
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 166 行定义.
|
inline |
在文件 lidar_point_label.h 第 74 行定义.
|
inline |
在文件 lidar_point_label.h 第 60 行定义.
bool apollo::perception::lidar::JudgeBlindTrafficCone | ( | const MlfTrackDataConstPtr & | track_data, |
double | frame_timestamp, | ||
const Eigen::Vector3d & | local_to_global_offset, | ||
Eigen::Affine3d & | lidar2world_pose, | ||
Eigen::Affine3d & | lidar2novatel_pose | ||
) |
|
inline |
在文件 pcl_util.h 第 54 行定义.
void apollo::perception::lidar::LoadPointCloud | ( | const std::string & | filename, |
typename pcl::PointCloud< PointT >::Ptr | point_cloud | ||
) |
在文件 pointcloud_util.h 第 70 行定义.
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 43 行定义.
void apollo::perception::lidar::MeasureAnchorPointVelocity | ( | TrackedObjectPtr | new_object, |
const TrackedObjectConstPtr & | old_object, | ||
const double & | time_diff | ||
) |
Measure anchor point velocity
new_object | for current updating |
old_object | for last updating |
time_diff | time interval from last updating |
在文件 measurement_collection.cc 第 28 行定义.
void apollo::perception::lidar::MeasureBboxCenterHistoryVelocity | ( | const MlfTrackDataConstPtr & | track_data, |
TrackedObjectPtr | new_object | ||
) |
在文件 measurement_collection.cc 第 69 行定义.
void apollo::perception::lidar::MeasureBboxCenterVelocity | ( | TrackedObjectPtr | new_object, |
const TrackedObjectConstPtr & | old_object, | ||
const double & | time_diff | ||
) |
Measure bbox center velocity
new_object | for current updating |
old_object | for last updating |
time_diff | time interval from last updating |
在文件 measurement_collection.cc 第 39 行定义.
void apollo::perception::lidar::MeasureBboxCornerHistoryVelocity | ( | const MlfTrackDataConstPtr & | track_data, |
TrackedObjectPtr | new_object | ||
) |
在文件 measurement_collection.cc 第 199 行定义.
void apollo::perception::lidar::MeasureBboxCornerVelocity | ( | TrackedObjectPtr | new_object, |
const TrackedObjectConstPtr & | old_object, | ||
const double & | time_diff | ||
) |
Measure bbox corner velocity
new_object | for current updating |
old_object | for last updating |
time_diff | time interval from last updating |
在文件 measurement_collection.cc 第 104 行定义.
void apollo::perception::lidar::MeasureObjectDetectionHistoryVelocity | ( | const MlfTrackDataConstPtr & | track_data, |
TrackedObjectPtr | new_object | ||
) |
在文件 measurement_collection.cc 第 322 行定义.
void apollo::perception::lidar::MeasureObjectDetectionVelocity | ( | TrackedObjectPtr | new_object, |
const TrackedObjectConstPtr & | old_object, | ||
const double & | time_diff | ||
) |
Measure object-detection center and corner velocity
new_object | for current updating |
old_object | for last updating |
time_diff | time interval from last updating |
在文件 measurement_collection.cc 第 313 行定义.
在文件 gnn_bipartite_graph_matcher.cc 第 37 行定义.
std::ostream & apollo::perception::lidar::operator<< | ( | std::ostream & | os, |
const MatchCost & | m | ||
) |
在文件 gnn_bipartite_graph_matcher.cc 第 41 行定义.
|
inline |
apollo::perception::lidar::PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER | ( | GnnBipartiteGraphMatcher | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_BIPARTITEGRAPHMATCHER | ( | MultiHmBipartiteGraphMatcher | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_CLASSIFIER | ( | FusedClassifier | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_GROUNDDETECTOR | ( | GroundServiceDetector | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_GROUNDDETECTOR | ( | SpatioTemporalGroundDetector | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_LIDARDETECTOR | ( | CenterPointDetection | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_LIDARDETECTOR | ( | CNNSegmentation | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_LIDARDETECTOR | ( | MaskPillarsDetection | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_LIDARDETECTOR | ( | PointPillarsDetection | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_MLFFILTER | ( | MlfMotionFilter | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_MLFFILTER | ( | MlfShapeFilter | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_MLFFILTER | ( | MlfTypeFilter | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_MULTITARGET_TRACKER | ( | MlfEngine | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_ONESHOTTYPEFUSION | ( | CCRFOneShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_ONESHOTTYPEFUSION | ( | CCRFSingleShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_POINTCLOUDPREPROCESSOR | ( | PointCloudPreprocessor | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseBipartiteGraphMatcher | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseClassifier | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseGroundDetector | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseLidarDetector | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseMultiShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseMultiTargetTracker | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseOneShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BasePointCloudPreprocessor | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseSequenceTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | BaseSingleShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | MlfBaseFilter | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | SceneService | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_REGISTERER | ( | SceneServiceContent | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SCENESERVICE | ( | GroundService | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SCENESERVICE | ( | ROIService | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SCENESERVICECONTENT | ( | GroundServiceContent | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SCENESERVICECONTENT | ( | ROIServiceContent | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SEQUENCETYPEFUSION | ( | CCRFMultiShotTypeFusion | ) |
apollo::perception::lidar::PERCEPTION_REGISTER_SEQUENCETYPEFUSION | ( | CCRFSequenceTypeFusion | ) |
|
inline |
float apollo::perception::lidar::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_object | object for computing distance |
track_predict | predicted state of track for computing distance |
new_object | new detected object for computing distance |
time_diff | time interval from last matching |
在文件 distance_collection.cc 第 147 行定义.
void apollo::perception::lidar::RemoveStaleDataFromMap | ( | double | timestamp, |
std::map< double, TrackedObjectPtr > * | data | ||
) |
在文件 mlf_track_data.cc 第 185 行定义.
|
inline |
在文件 lidar_point_label.h 第 65 行定义.
|
inline |
在文件 lidar_point_label.h 第 51 行定义.
|
inline |
在文件 pcl_util.h 第 114 行定义.
|
inline |
在文件 pcl_util.h 第 100 行定义.
|
inline |
在文件 pcl_util.h 第 74 行定义.
struct apollo::perception::lidar::PointCloudPreprocessorOptions apollo::perception::lidar::EIGEN_ALIGN16 |
const double apollo::perception::lidar::kPI = 3.1415926535897932384626433832795 |
const float apollo::perception::lidar::STATIC_VELOCITY = 0.01 |
在文件 mlf_motion_measurement.cc 第 31 行定义.