Apollo 10.0
自动驾驶开放平台
|
函数 | |
template<typename T > | |
std::enable_if< std::is_integral< T >::value, bool >::type | Equal (const T &lhs, const T &rhs) |
template<typename T > | |
std::enable_if< std::is_floating_point< T >::value, bool >::type | Equal (const T &lhs, const T &rhs) |
void | GetMaxScoreIndex (const std::vector< float > &scores, const float threshold, const int top_k, std::vector< std::pair< float, int > > *score_index_vec) |
template<typename BoxType > | |
void | Nms (const std::vector< BoxType > &bboxes, const std::vector< float > &scores, const float score_threshold, const float nms_threshold, const float eta, const int top_k, std::vector< int > *indices, float(*ComputeOverlap)(const BoxType &, const BoxType &), int limit=std::numeric_limits< int >::max) |
__attribute__ ((constructor)) void PoolInitialize() | |
bool | DownSamplePointCloudBeams (base::PointFCloudPtr cloud_ptr, base::PointFCloudPtr out_cloud_ptr, int downsample_factor) |
void | GetPointCloudCentroid (const PointFCloud &cloud, PointF *centroid) |
void | CloudDemean (PointFCloud *pc) |
double | OrientCloud (const PointFCloud &pc, PointFCloud *pc_out, bool demean) |
bool | GetPointCloudMinareaBbox (const PointFCloud &pc, BoundingCube *box, const int &min_num_points, const bool &verbose) |
void | CloudDemean (base::PointFCloudPtr cloud) |
void | GetPointCloudCentroid (base::PointFCloudConstPtr cloud, PointF *centroid) |
std::ostream & | operator<< (std::ostream &o, const Polynomial &p) |
void | PerceptionMallocHost (void **ptr, size_t size, bool use_cuda) |
void | PerceptionFreeHost (void *ptr, bool use_cuda) |
typedef std::shared_ptr<const BaseCameraModel> apollo::perception::base::BaseCameraModelConstPtr |
typedef std::shared_ptr<BaseCameraModel> apollo::perception::base::BaseCameraModelPtr |
typedef BBox2D<double> apollo::perception::base::BBox2DD |
typedef BBox2D<float> apollo::perception::base::BBox2DF |
typedef BBox2D<int> apollo::perception::base::BBox2DI |
using apollo::perception::base::BlobConstPtr = typedef std::shared_ptr<const Blob<Dtype> > |
using apollo::perception::base::BlobPtr = typedef std::shared_ptr<Blob<Dtype> > |
using apollo::perception::base::BrownCameraDistortionModelConstPtr = typedef std::shared_ptr<const BrownCameraDistortionModel> |
在文件 distortion_model.h 第 91 行定义.
using apollo::perception::base::BrownCameraDistortionModelPtr = typedef std::shared_ptr<BrownCameraDistortionModel> |
在文件 distortion_model.h 第 88 行定义.
typedef std::shared_ptr<const CameraFrameSupplement> apollo::perception::base::CameraFrameSupplementConstPtr |
在文件 frame_supplement.h 第 74 行定义.
typedef std::shared_ptr<CameraFrameSupplement> apollo::perception::base::CameraFrameSupplementPtr |
在文件 frame_supplement.h 第 72 行定义.
typedef std::shared_ptr<const CameraObjectSupplement> apollo::perception::base::CameraObjectSupplementConstPtr |
在文件 object_supplement.h 第 251 行定义.
typedef std::shared_ptr<CameraObjectSupplement> apollo::perception::base::CameraObjectSupplementPtr |
在文件 object_supplement.h 第 249 行定义.
typedef std::shared_ptr<const Frame> apollo::perception::base::FrameConstPtr |
using apollo::perception::base::FramePool = typedef ConcurrentObjectPool<Frame, kFramePoolSize, FrameInitializer> |
在文件 object_pool_types.h 第 72 行定义.
typedef std::shared_ptr<Frame> apollo::perception::base::FramePtr |
using apollo::perception::base::HdmapStructConstPtr = typedef std::shared_ptr<const HdmapStruct> |
在文件 hdmap_struct.h 第 46 行定义.
using apollo::perception::base::HdmapStructPtr = typedef std::shared_ptr<HdmapStruct> |
在文件 hdmap_struct.h 第 45 行定义.
typedef std::shared_ptr<const Image8U> apollo::perception::base::Image8UConstPtr |
在文件 image_8u.h 第 149 行定义.
typedef std::shared_ptr<Image8U> apollo::perception::base::Image8UPtr |
在文件 image_8u.h 第 148 行定义.
typedef std::shared_ptr<const LidarFrameSupplement> apollo::perception::base::LidarFrameSupplementConstPtr |
在文件 frame_supplement.h 第 44 行定义.
typedef std::shared_ptr<LidarFrameSupplement> apollo::perception::base::LidarFrameSupplementPtr |
在文件 frame_supplement.h 第 42 行定义.
typedef std::shared_ptr<const LidarObjectSupplement> apollo::perception::base::LidarObjectSupplementConstPtr |
在文件 object_supplement.h 第 91 行定义.
typedef std::shared_ptr<LidarObjectSupplement> apollo::perception::base::LidarObjectSupplementPtr |
在文件 object_supplement.h 第 89 行定义.
typedef boost::circular_buffer<Vehicle3DStatus> apollo::perception::base::Motion3DBuffer |
在文件 object_supplement.h 第 287 行定义.
typedef std::shared_ptr<const Motion3DBuffer> apollo::perception::base::Motion3DBufferConstPtr |
在文件 object_supplement.h 第 289 行定义.
typedef std::shared_ptr<Motion3DBuffer> apollo::perception::base::Motion3DBufferPtr |
在文件 object_supplement.h 第 288 行定义.
typedef boost::circular_buffer<VehicleStatus> apollo::perception::base::MotionBuffer |
在文件 object_supplement.h 第 269 行定义.
typedef std::shared_ptr<const MotionBuffer> apollo::perception::base::MotionBufferConstPtr |
在文件 object_supplement.h 第 271 行定义.
typedef std::shared_ptr<MotionBuffer> apollo::perception::base::MotionBufferPtr |
在文件 object_supplement.h 第 270 行定义.
typedef Eigen::Matrix4f apollo::perception::base::MotionType |
在文件 object_supplement.h 第 253 行定义.
using apollo::perception::base::ObjectConstPtr = typedef std::shared_ptr<const Object> |
using apollo::perception::base::ObjectPool = typedef ConcurrentObjectPool<Object, kObjectPoolSize, ObjectInitializer> |
在文件 object_pool_types.h 第 54 行定义.
using apollo::perception::base::ObjectPtr = typedef std::shared_ptr<Object> |
typedef std::shared_ptr<const PinholeCameraModel> apollo::perception::base::PinholeCameraModelConstPtr |
typedef std::shared_ptr<PinholeCameraModel> apollo::perception::base::PinholeCameraModelPtr |
using apollo::perception::base::Point2DD = typedef Point2D<double> |
using apollo::perception::base::Point2DF = typedef Point2D<float> |
using apollo::perception::base::Point2DI = typedef Point2D<int> |
using apollo::perception::base::Point3DD = typedef Point3D<double> |
using apollo::perception::base::Point3DF = typedef Point3D<float> |
using apollo::perception::base::Point3DI = typedef Point3D<int> |
using apollo::perception::base::PointD = typedef Point<double> |
在文件 point_cloud.h 第 515 行定义.
typedef std::shared_ptr<const PointDCloud> apollo::perception::base::PointDCloudConstPtr |
在文件 point_cloud.h 第 521 行定义.
using apollo::perception::base::PointDCloudPool = typedef ConcurrentObjectPool<AttributePointCloud<PointD>, kPointCloudPoolSize, PointCloudInitializer<double> > |
在文件 object_pool_types.h 第 60 行定义.
typedef std::shared_ptr<PointDCloud> apollo::perception::base::PointDCloudPtr |
在文件 point_cloud.h 第 520 行定义.
using apollo::perception::base::PointF = typedef Point<float> |
在文件 point_cloud.h 第 514 行定义.
typedef std::shared_ptr<const PointFCloud> apollo::perception::base::PointFCloudConstPtr |
在文件 point_cloud.h 第 518 行定义.
using apollo::perception::base::PointFCloudPool = typedef ConcurrentObjectPool<AttributePointCloud<PointF>, kPointCloudPoolSize, PointCloudInitializer<float> > |
在文件 object_pool_types.h 第 56 行定义.
typedef std::shared_ptr<PointFCloud> apollo::perception::base::PointFCloudPtr |
在文件 point_cloud.h 第 517 行定义.
typedef std::shared_ptr< const PointIndices > apollo::perception::base::PointIndicesConstPtr |
在文件 point_cloud.h 第 511 行定义.
typedef std::shared_ptr< PointIndices > apollo::perception::base::PointIndicesPtr |
在文件 point_cloud.h 第 510 行定义.
using apollo::perception::base::PointXYZID = typedef Point<double> |
using apollo::perception::base::PointXYZIF = typedef Point<float> |
using apollo::perception::base::PointXYZITD = typedef PointXYZIT<double> |
using apollo::perception::base::PointXYZITF = typedef PointXYZIT<float> |
using apollo::perception::base::PointXYZITHBD = typedef PointXYZITHB<double> |
using apollo::perception::base::PointXYZITHBF = typedef PointXYZITHB<float> |
using apollo::perception::base::PointXYZITHBLD = typedef PointXYZITHBL<double> |
using apollo::perception::base::PointXYZITHBLF = typedef PointXYZITHBL<float> |
using apollo::perception::base::PointXYZITHD = typedef PointXYZITH<double> |
using apollo::perception::base::PointXYZITHF = typedef PointXYZITH<float> |
在文件 point_cloud.h 第 525 行定义.
typedef std::shared_ptr<const PolygonDType> apollo::perception::base::PolygonDTypeConstPtr |
在文件 point_cloud.h 第 531 行定义.
typedef std::shared_ptr<PolygonDType> apollo::perception::base::PolygonDTypePtr |
在文件 point_cloud.h 第 530 行定义.
在文件 point_cloud.h 第 524 行定义.
typedef std::shared_ptr<const PolygonFType> apollo::perception::base::PolygonFTypeConstPtr |
在文件 point_cloud.h 第 528 行定义.
typedef std::shared_ptr<PolygonFType> apollo::perception::base::PolygonFTypePtr |
在文件 point_cloud.h 第 527 行定义.
typedef std::shared_ptr<const Radar4dObjectSupplement> apollo::perception::base::Radar4dObjectSupplementConstPtr |
在文件 object_supplement.h 第 139 行定义.
typedef std::shared_ptr<Radar4dObjectSupplement> apollo::perception::base::Radar4dObjectSupplementPtr |
在文件 object_supplement.h 第 137 行定义.
typedef std::shared_ptr<const RadarFrameSupplement> apollo::perception::base::RadarFrameSupplementConstPtr |
在文件 frame_supplement.h 第 53 行定义.
typedef std::shared_ptr<RadarFrameSupplement> apollo::perception::base::RadarFrameSupplementPtr |
在文件 frame_supplement.h 第 51 行定义.
typedef std::shared_ptr<const RadarObjectSupplement> apollo::perception::base::RadarObjectSupplementConstPtr |
在文件 object_supplement.h 第 165 行定义.
typedef std::shared_ptr<RadarObjectSupplement> apollo::perception::base::RadarObjectSupplementPtr |
在文件 object_supplement.h 第 163 行定义.
using apollo::perception::base::RadarPointD = typedef RadarPoint<double> |
在文件 radar_point_cloud.h 第 403 行定义.
typedef std::shared_ptr<const RadarPointDCloud> apollo::perception::base::RadarPointDCloudConstPtr |
在文件 radar_point_cloud.h 第 409 行定义.
using apollo::perception::base::RadarPointDCloudPool = typedef ConcurrentObjectPool<AttributeRadarPointCloud<RadarPointD>, kPointCloudPoolSize, RadarPointCloudInitializer<double> > |
在文件 object_pool_types.h 第 68 行定义.
typedef std::shared_ptr<RadarPointDCloud> apollo::perception::base::RadarPointDCloudPtr |
在文件 radar_point_cloud.h 第 408 行定义.
using apollo::perception::base::RadarPointF = typedef RadarPoint<float> |
在文件 radar_point_cloud.h 第 402 行定义.
typedef std::shared_ptr<const RadarPointFCloud> apollo::perception::base::RadarPointFCloudConstPtr |
在文件 radar_point_cloud.h 第 406 行定义.
using apollo::perception::base::RadarPointFCloudPool = typedef ConcurrentObjectPool<AttributeRadarPointCloud<RadarPointF>, kPointCloudPoolSize, RadarPointCloudInitializer<double> > |
在文件 object_pool_types.h 第 64 行定义.
typedef std::shared_ptr<RadarPointFCloud> apollo::perception::base::RadarPointFCloudPtr |
在文件 radar_point_cloud.h 第 405 行定义.
using apollo::perception::base::RadarPointXYZVRD = typedef RadarPoint<double> |
using apollo::perception::base::RadarPointXYZVRF = typedef RadarPoint<float> |
在文件 radar_point_cloud.h 第 413 行定义.
typedef std::shared_ptr<const RadarPolygonDType> apollo::perception::base::RadarPolygonDTypeConstPtr |
在文件 radar_point_cloud.h 第 419 行定义.
typedef std::shared_ptr<RadarPolygonDType> apollo::perception::base::RadarPolygonDTypePtr |
在文件 radar_point_cloud.h 第 418 行定义.
在文件 radar_point_cloud.h 第 412 行定义.
typedef std::shared_ptr<const RadarPolygonFType> apollo::perception::base::RadarPolygonFTypeConstPtr |
在文件 radar_point_cloud.h 第 416 行定义.
typedef std::shared_ptr<RadarPolygonFType> apollo::perception::base::RadarPolygonFTypePtr |
在文件 radar_point_cloud.h 第 415 行定义.
typedef Rect<double> apollo::perception::base::RectD |
typedef Rect<float> apollo::perception::base::RectF |
typedef Rect<int> apollo::perception::base::RectI |
typedef ::testing::Types<float, double> apollo::perception::base::TestDtypes |
在文件 test_helper.h 第 38 行定义.
typedef ::testing::Types<CPUDevice<float>, CPUDevice<double> > apollo::perception::base::TestDtypesAndDevices |
在文件 test_helper.h 第 52 行定义.
typedef std::shared_ptr<TrafficLight> apollo::perception::base::TrafficLightPtr |
在文件 traffic_light.h 第 88 行定义.
typedef std::vector<TrafficLightPtr> apollo::perception::base::TrafficLightPtrs |
在文件 traffic_light.h 第 89 行定义.
typedef std::shared_ptr<const UltrasonicFrameSupplement> apollo::perception::base::UltrasonicFrameSupplementConstPtr |
在文件 frame_supplement.h 第 91 行定义.
typedef std::shared_ptr<UltrasonicFrameSupplement> apollo::perception::base::UltrasonicFrameSupplementPtr |
在文件 frame_supplement.h 第 89 行定义.
|
strong |
枚举值 | |
---|---|
NONE | |
GRAY | |
RGB | |
BGR |
在文件 image_8u.h 第 28 行定义.
|
strong |
枚举值 | |
---|---|
INT_BACKGROUND | |
INT_SMALLMOT | |
INT_PEDESTRIAN | |
INT_NONMOT | |
INT_BIGMOT | |
INT_UNKNOWN | |
INT_MAX_OBJECT_TYPE |
在文件 object_types.h 第 51 行定义.
|
strong |
Definition of the position of a lane marking in respect to the ego lane.
在文件 lane_struct.h 第 34 行定义.
|
strong |
枚举值 | |
---|---|
WHITE_DASHED | |
WHITE_SOLID | |
YELLOW_DASHED | |
YELLOW_SOLID |
在文件 lane_struct.h 第 26 行定义.
|
strong |
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
MOVING | |
STATIONARY | |
MAX_MOTION_STATE |
在文件 object_types.h 第 99 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
IGNORE | |
GROUND | |
OBJECT | |
CURB | |
VEGETATION | |
FENCE | |
NOISE | |
WALL | |
MAX_OBJECT_SEMANTIC_LABEL |
在文件 object_types.h 第 37 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
UNKNOWN_MOVABLE | |
UNKNOWN_UNMOVABLE | |
CAR | |
VAN | |
TRUCK | |
BUS | |
CYCLIST | |
MOTORCYCLIST | |
TRICYCLIST | |
PEDESTRIAN | |
TRAFFICCONE | |
SMALLMOT | |
BIGMOT | |
NONMOT | |
MAX_OBJECT_TYPE |
在文件 object_types.h 第 77 行定义.
|
strong |
枚举值 | |
---|---|
UNKNOWN | |
UNKNOWN_MOVABLE | |
UNKNOWN_UNMOVABLE | |
PEDESTRIAN | |
BICYCLE | |
VEHICLE | |
MAX_OBJECT_TYPE |
在文件 object_types.h 第 26 行定义.
|
strong |
枚举值 | |
---|---|
FRONT | |
LEFT_FORWARD | |
LEFT | |
LEFT_BACKWARD | |
REAR | |
RIGHT_BACKWARD | |
RIGHT | |
RIGHT_FORWARD | |
PANORAMIC |
在文件 sensor_meta.h 第 45 行定义.
|
strong |
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has same id with SensorMeta, which defined in the proto of sensor_manager
枚举值 | |
---|---|
UNKNOWN_SENSOR_TYPE | |
VELODYNE_128 | |
VELODYNE_64 | |
VELODYNE_32 | |
VELODYNE_16 | |
LDLIDAR_4 | |
LDLIDAR_1 | |
SHORT_RANGE_RADAR | |
LONG_RANGE_RADAR | |
MONOCULAR_CAMERA | |
STEREO_CAMERA | |
ULTRASONIC | |
SENSOR_TYPE_NUM |
在文件 sensor_meta.h 第 29 行定义.
|
strong |
枚举值 | |
---|---|
TL_UNKNOWN_COLOR | |
TL_RED | |
TL_YELLOW | |
TL_GREEN | |
TL_BLACK | |
TL_TOTAL_COLOR_NUM |
在文件 traffic_light.h 第 28 行定义.
|
strong |
枚举值 | |
---|---|
TL_UNKNOWN_CLASS | |
TL_VERTICAL_CLASS | |
TL_QUADRATE_CLASS | |
TL_HORIZONTAL_CLASS |
在文件 traffic_light.h 第 37 行定义.
|
strong |
Landmark types and mapping
枚举值 | |
---|---|
RoadArrow | |
RoadText | |
TrafficSign | |
TrafficLight | |
MAX_LANDMARK_TYPE |
在文件 object_types.h 第 109 行定义.
|
strong |
枚举值 | |
---|---|
CAR | |
VAN | |
BUS | |
TRUCK | |
BICYCLE | |
TRICYCLE | |
PEDESTRIAN | |
TRAFFICCONE | |
UNKNOWN_MOVABLE | |
UNKNOWN_UNMOVABLE | |
MAX_OBJECT_TYPE |
在文件 object_types.h 第 62 行定义.
apollo::perception::base::__attribute__ | ( | (constructor) | ) |
在文件 object_pool_types.cc 第 25 行定义.
void apollo::perception::base::CloudDemean | ( | base::PointFCloudPtr | cloud | ) |
void apollo::perception::base::CloudDemean | ( | PointFCloud * | pc | ) |
在文件 point_cloud_util.cc 第 59 行定义.
bool apollo::perception::base::DownSamplePointCloudBeams | ( | base::PointFCloudPtr | cloud_ptr, |
base::PointFCloudPtr | out_cloud_ptr, | ||
int | downsample_factor | ||
) |
在文件 point_cloud_util.cc 第 29 行定义.
std::enable_if< std::is_integral< T >::value, bool >::type apollo::perception::base::Equal | ( | const T & | lhs, |
const T & | rhs | ||
) |
在文件 comparison_traits.h 第 28 行定义.
std::enable_if< std::is_floating_point< T >::value, bool >::type apollo::perception::base::Equal | ( | const T & | lhs, |
const T & | rhs | ||
) |
在文件 comparison_traits.h 第 35 行定义.
void apollo::perception::base::GetMaxScoreIndex | ( | const std::vector< float > & | scores, |
const float | threshold, | ||
const int | top_k, | ||
std::vector< std::pair< float, int > > * | score_index_vec | ||
) |
void apollo::perception::base::GetPointCloudCentroid | ( | base::PointFCloudConstPtr | cloud, |
PointF * | centroid | ||
) |
void apollo::perception::base::GetPointCloudCentroid | ( | const PointFCloud & | cloud, |
PointF * | centroid | ||
) |
在文件 point_cloud_util.cc 第 48 行定义.
bool apollo::perception::base::GetPointCloudMinareaBbox | ( | const PointFCloud & | pc, |
BoundingCube * | box, | ||
const int & | min_num_points, | ||
const bool & | verbose | ||
) |
在文件 point_cloud_util.cc 第 93 行定义.
void apollo::perception::base::Nms | ( | const std::vector< BoxType > & | bboxes, |
const std::vector< float > & | scores, | ||
const float | score_threshold, | ||
const float | nms_threshold, | ||
const float | eta, | ||
const int | top_k, | ||
std::vector< int > * | indices, | ||
float(*)(const BoxType &, const BoxType &) | ComputeOverlap, | ||
int | limit = std::numeric_limits<int>::max |
||
) |
std::ostream & apollo::perception::base::operator<< | ( | std::ostream & | o, |
const Polynomial & | p | ||
) |
在文件 polynomial.cc 第 71 行定义.
double apollo::perception::base::OrientCloud | ( | const PointFCloud & | pc, |
PointFCloud * | pc_out, | ||
bool | demean | ||
) |
在文件 point_cloud_util.cc 第 70 行定义.
|
inline |
在文件 syncedmem.h 第 83 行定义.
|
inline |
在文件 syncedmem.h 第 72 行定义.
struct apollo::perception::base::ImpendingCollisionEdges apollo::perception::base::EIGEN_ALIGN16 |
const std::map<Color, int> apollo::perception::base::kChannelsMap |
在文件 image_8u.h 第 35 行定义.
const std::map<std::string, ObjectSemanticType> apollo::perception::base::kName2ObjectSemanticTypeMap |
在文件 object_types.h 第 169 行定义.
const std::map<std::string, ObjectSubType> apollo::perception::base::kName2SubTypeMap |
在文件 object_types.h 第 265 行定义.
const std::map<std::string, ObjectType> apollo::perception::base::kObjectName2TypeMap |
在文件 object_types.h 第 144 行定义.
const std::map<ObjectSemanticType, std::string> apollo::perception::base::kObjectSemanticType2NameMap |
ObjectSemanticType mapping
在文件 object_types.h 第 156 行定义.
const std::map<ObjectType, std::string> apollo::perception::base::kObjectType2NameMap |
ObjectType mapping
在文件 object_types.h 第 135 行定义.
const std::map<ObjectSubType, std::string> apollo::perception::base::kSubType2NameMap |
在文件 object_types.h 第 249 行定义.
const std::map<ObjectSubType, ObjectType> apollo::perception::base::kSubType2TypeMap |
ObjectSubType mapping
在文件 object_types.h 第 230 行定义.
const std::map<std::string, base::VisualLandmarkType> apollo::perception::base::kVisualLandmarkName2TypeMap |
在文件 object_types.h 第 125 行定义.
const std::map<VisualLandmarkType, std::string> apollo::perception::base::kVisualLandmarkType2NameMap |
在文件 object_types.h 第 117 行定义.
const std::map<std::string, base::VisualObjectType> apollo::perception::base::kVisualName2TypeMap |
在文件 object_types.h 第 213 行定义.
const std::map<VisualObjectType, std::string> apollo::perception::base::kVisualType2NameMap |
在文件 object_types.h 第 199 行定义.
const std::map<VisualObjectType, ObjectType> apollo::perception::base::kVisualTypeMap |
VisualObjectType mapping
在文件 object_types.h 第 185 行定义.