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

class  AttributePointCloud
 
class  AttributeRadarPointCloud
 
class  BaseCameraDistortionModel
 
class  BaseCameraModel
 
class  BaseObjectPool
 
struct  BBox2D
 
class  Blob
 A wrapper around SyncedMemory holders serving as the basic computational unit for images, feature maps, etc. 更多...
 
struct  BoundingCube
 
class  BrownCameraDistortionModel
 
struct  CameraFrameSupplement
 
struct  CameraObjectSupplement
 
struct  CarLight
 
class  ConcurrentObjectPool
 
struct  CPUDevice
 
class  CPUDeviceTest
 
class  DummyObjectPool
 
struct  EndPoints
 
struct  Frame
 
struct  FrameInitializer
 
struct  FusionObjectSupplement
 
struct  HdmapStruct
 
class  Image8U
 A wrapper around Blob holders serving as the basic computational unit for images. 更多...
 
struct  ImpendingCollisionEdge
 
struct  ImpendingCollisionEdges
 
struct  Landmark
 
struct  LaneBoundary
 
struct  LaneLine
 
struct  LaneLineCubicCurve
 
struct  LidarFrameSupplement
 
struct  LidarObjectSupplement
 
class  LightObjectPool
 
struct  LightRegion
 
struct  LightStatus
 
class  MultiDeviceTest
 
struct  Object
 
struct  ObjectInitializer
 
struct  ObjectPoolDefaultInitializer
 
class  OmnidirectionalCameraDistortionModel
 
class  PinholeCameraModel
 
struct  Point
 
struct  Point2D
 
struct  Point3D
 
class  PointCloud
 
struct  PointCloudInitializer
 
struct  PointIndices
 
struct  PointXYZIT
 
struct  PointXYZITH
 
struct  PointXYZITHB
 
struct  PointXYZITHBL
 
class  Polynomial
 
struct  Radar4dObjectSupplement
 
struct  RadarFrameSupplement
 
struct  RadarObjectSupplement
 
struct  RadarPoint
 
class  RadarPointCloud
 
struct  RadarPointCloudInitializer
 
struct  Rect
 
struct  RoadBoundary
 
struct  SensorInfo
 
struct  SensorObjectMeasurement
 
class  SyncedMemory
 Manages memory allocation and synchronization between the host (CPU) and device (GPU). 更多...
 
struct  TrafficLight
 
struct  UltrasonicFrameSupplement
 
struct  Vehicle3DStatus
 
struct  VehicleStatus
 

类型定义

template<typename Dtype >
using BlobPtr = std::shared_ptr< Blob< Dtype > >
 
template<typename Dtype >
using BlobConstPtr = std::shared_ptr< const Blob< Dtype > >
 
typedef Rect< int > RectI
 
typedef Rect< float > RectF
 
typedef Rect< double > RectD
 
typedef BBox2D< int > BBox2DI
 
typedef BBox2D< float > BBox2DF
 
typedef BBox2D< double > BBox2DD
 
typedef std::shared_ptr< BaseCameraModelBaseCameraModelPtr
 
typedef std::shared_ptr< const BaseCameraModelBaseCameraModelConstPtr
 
typedef std::shared_ptr< PinholeCameraModelPinholeCameraModelPtr
 
typedef std::shared_ptr< const PinholeCameraModelPinholeCameraModelConstPtr
 
using BrownCameraDistortionModelPtr = std::shared_ptr< BrownCameraDistortionModel >
 
using BrownCameraDistortionModelConstPtr = std::shared_ptr< const BrownCameraDistortionModel >
 
typedef std::shared_ptr< FrameFramePtr
 
typedef std::shared_ptr< const FrameFrameConstPtr
 
typedef std::shared_ptr< LidarFrameSupplementLidarFrameSupplementPtr
 
typedef std::shared_ptr< const LidarFrameSupplementLidarFrameSupplementConstPtr
 
typedef std::shared_ptr< RadarFrameSupplementRadarFrameSupplementPtr
 
typedef std::shared_ptr< const RadarFrameSupplementRadarFrameSupplementConstPtr
 
typedef std::shared_ptr< CameraFrameSupplementCameraFrameSupplementPtr
 
typedef std::shared_ptr< const CameraFrameSupplementCameraFrameSupplementConstPtr
 
typedef std::shared_ptr< UltrasonicFrameSupplementUltrasonicFrameSupplementPtr
 
typedef std::shared_ptr< const UltrasonicFrameSupplementUltrasonicFrameSupplementConstPtr
 
using HdmapStructPtr = std::shared_ptr< HdmapStruct >
 
using HdmapStructConstPtr = std::shared_ptr< const HdmapStruct >
 
typedef std::shared_ptr< Image8UImage8UPtr
 
typedef std::shared_ptr< const Image8UImage8UConstPtr
 
using ObjectPtr = std::shared_ptr< Object >
 
using ObjectConstPtr = std::shared_ptr< const Object >
 
using ObjectPool = ConcurrentObjectPool< Object, kObjectPoolSize, ObjectInitializer >
 
using PointFCloudPool = ConcurrentObjectPool< AttributePointCloud< PointF >, kPointCloudPoolSize, PointCloudInitializer< float > >
 
using PointDCloudPool = ConcurrentObjectPool< AttributePointCloud< PointD >, kPointCloudPoolSize, PointCloudInitializer< double > >
 
using RadarPointFCloudPool = ConcurrentObjectPool< AttributeRadarPointCloud< RadarPointF >, kPointCloudPoolSize, RadarPointCloudInitializer< double > >
 
using RadarPointDCloudPool = ConcurrentObjectPool< AttributeRadarPointCloud< RadarPointD >, kPointCloudPoolSize, RadarPointCloudInitializer< double > >
 
using FramePool = ConcurrentObjectPool< Frame, kFramePoolSize, FrameInitializer >
 
typedef std::shared_ptr< LidarObjectSupplementLidarObjectSupplementPtr
 
typedef std::shared_ptr< const LidarObjectSupplementLidarObjectSupplementConstPtr
 
typedef std::shared_ptr< Radar4dObjectSupplementRadar4dObjectSupplementPtr
 
typedef std::shared_ptr< const Radar4dObjectSupplementRadar4dObjectSupplementConstPtr
 
typedef std::shared_ptr< RadarObjectSupplementRadarObjectSupplementPtr
 
typedef std::shared_ptr< const RadarObjectSupplementRadarObjectSupplementConstPtr
 
typedef std::shared_ptr< CameraObjectSupplementCameraObjectSupplementPtr
 
typedef std::shared_ptr< const CameraObjectSupplementCameraObjectSupplementConstPtr
 
typedef Eigen::Matrix4f MotionType
 
typedef boost::circular_buffer< VehicleStatusMotionBuffer
 
typedef std::shared_ptr< MotionBufferMotionBufferPtr
 
typedef std::shared_ptr< const MotionBufferMotionBufferConstPtr
 
typedef boost::circular_buffer< Vehicle3DStatusMotion3DBuffer
 
typedef std::shared_ptr< Motion3DBufferMotion3DBufferPtr
 
typedef std::shared_ptr< const Motion3DBufferMotion3DBufferConstPtr
 
using PointF = Point< float >
 
using PointD = Point< double >
 
using PointXYZIF = Point< float >
 
using PointXYZID = Point< double >
 
using PointXYZITF = PointXYZIT< float >
 
using PointXYZITD = PointXYZIT< double >
 
using PointXYZITHF = PointXYZITH< float >
 
using PointXYZITHD = PointXYZITH< double >
 
using PointXYZITHBF = PointXYZITHB< float >
 
using PointXYZITHBD = PointXYZITHB< double >
 
using PointXYZITHBLF = PointXYZITHBL< float >
 
using PointXYZITHBLD = PointXYZITHBL< double >
 
using Point2DF = Point2D< float >
 
using Point2DI = Point2D< int >
 
using Point2DD = Point2D< double >
 
using Point3DF = Point3D< float >
 
using Point3DI = Point3D< int >
 
using Point3DD = Point3D< double >
 
using RadarPointF = RadarPoint< float >
 
using RadarPointD = RadarPoint< double >
 
using RadarPointXYZVRF = RadarPoint< float >
 
using RadarPointXYZVRD = RadarPoint< double >
 
typedef std::shared_ptr< PointIndicesPointIndicesPtr
 
typedef std::shared_ptr< const PointIndicesPointIndicesConstPtr
 
typedef AttributePointCloud< PointFPointFCloud
 
typedef AttributePointCloud< PointDPointDCloud
 
typedef std::shared_ptr< PointFCloudPointFCloudPtr
 
typedef std::shared_ptr< const PointFCloudPointFCloudConstPtr
 
typedef std::shared_ptr< PointDCloudPointDCloudPtr
 
typedef std::shared_ptr< const PointDCloudPointDCloudConstPtr
 
typedef PointCloud< PointFPolygonFType
 
typedef PointCloud< PointDPolygonDType
 
typedef std::shared_ptr< PolygonFTypePolygonFTypePtr
 
typedef std::shared_ptr< const PolygonFTypePolygonFTypeConstPtr
 
typedef std::shared_ptr< PolygonDTypePolygonDTypePtr
 
typedef std::shared_ptr< const PolygonDTypePolygonDTypeConstPtr
 
typedef AttributeRadarPointCloud< RadarPointFRadarPointFCloud
 
typedef AttributeRadarPointCloud< RadarPointDRadarPointDCloud
 
typedef std::shared_ptr< RadarPointFCloudRadarPointFCloudPtr
 
typedef std::shared_ptr< const RadarPointFCloudRadarPointFCloudConstPtr
 
typedef std::shared_ptr< RadarPointDCloudRadarPointDCloudPtr
 
typedef std::shared_ptr< const RadarPointDCloudRadarPointDCloudConstPtr
 
typedef RadarPointCloud< PointFRadarPolygonFType
 
typedef RadarPointCloud< PointDRadarPolygonDType
 
typedef std::shared_ptr< RadarPolygonFTypeRadarPolygonFTypePtr
 
typedef std::shared_ptr< const RadarPolygonFTypeRadarPolygonFTypeConstPtr
 
typedef std::shared_ptr< RadarPolygonDTypeRadarPolygonDTypePtr
 
typedef std::shared_ptr< const RadarPolygonDTypeRadarPolygonDTypeConstPtr
 
typedef ::testing::Types< float, double > TestDtypes
 
typedef ::testing::Types< CPUDevice< float >, CPUDevice< double > > TestDtypesAndDevices
 
typedef std::shared_ptr< TrafficLightTrafficLightPtr
 
typedef std::vector< TrafficLightPtrTrafficLightPtrs
 

枚举

enum class  Color { NONE = 0x00 , GRAY = 0x01 , RGB = 0x02 , BGR = 0x03 }
 
enum class  LaneLineType { WHITE_DASHED = 0 , WHITE_SOLID , YELLOW_DASHED , YELLOW_SOLID }
 
enum class  LaneLinePositionType {
  CURB_LEFT = -5 , FOURTH_LEFT = -4 , THIRD_LEFT = -3 , ADJACENT_LEFT = -2 ,
  EGO_LEFT = -1 , EGO_CENTER = 0 , EGO_RIGHT = 1 , ADJACENT_RIGHT = 2 ,
  THIRD_RIGHT = 3 , FOURTH_RIGHT = 4 , CURB_RIGHT = 5 , OTHER = 6 ,
  UNKNOWN = 7
}
 Definition of the position of a lane marking in respect to the ego lane. 更多...
 
enum class  LaneLineUseType { REAL = 0 , VIRTUAL }
 
enum class  ObjectType {
  UNKNOWN = 0 , UNKNOWN_MOVABLE = 1 , UNKNOWN_UNMOVABLE = 2 , PEDESTRIAN = 3 ,
  BICYCLE = 4 , VEHICLE = 5 , MAX_OBJECT_TYPE = 6
}
 
enum class  ObjectSemanticType {
  UNKNOWN = 0 , IGNORE = 1 , GROUND = 2 , OBJECT = 3 ,
  CURB = 4 , VEGETATION = 5 , FENCE = 6 , NOISE = 7 ,
  WALL = 8 , MAX_OBJECT_SEMANTIC_LABEL = 9
}
 
enum class  InternalObjectType {
  INT_BACKGROUND = 0 , INT_SMALLMOT = 1 , INT_PEDESTRIAN = 2 , INT_NONMOT = 3 ,
  INT_BIGMOT = 4 , INT_UNKNOWN = 5 , INT_MAX_OBJECT_TYPE = 6
}
 
enum class  VisualObjectType {
  CAR , VAN , BUS , TRUCK ,
  BICYCLE , TRICYCLE , PEDESTRIAN , TRAFFICCONE ,
  UNKNOWN_MOVABLE , UNKNOWN_UNMOVABLE , MAX_OBJECT_TYPE
}
 
enum class  ObjectSubType {
  UNKNOWN = 0 , UNKNOWN_MOVABLE = 1 , UNKNOWN_UNMOVABLE = 2 , CAR = 3 ,
  VAN = 4 , TRUCK = 5 , BUS = 6 , CYCLIST = 7 ,
  MOTORCYCLIST = 8 , TRICYCLIST = 9 , PEDESTRIAN = 10 , TRAFFICCONE = 11 ,
  SMALLMOT = 12 , BIGMOT = 13 , NONMOT = 14 , MAX_OBJECT_TYPE = 15
}
 
enum class  MotionState { UNKNOWN = 0 , MOVING = 1 , STATIONARY = 2 , MAX_MOTION_STATE }
 
enum class  VisualLandmarkType {
  RoadArrow , RoadText , TrafficSign , TrafficLight ,
  MAX_LANDMARK_TYPE
}
 Landmark types and mapping 更多...
 
enum class  SensorType {
  UNKNOWN_SENSOR_TYPE = -1 , VELODYNE_128 = 0 , VELODYNE_64 = 1 , VELODYNE_32 = 2 ,
  VELODYNE_16 = 3 , LDLIDAR_4 = 4 , LDLIDAR_1 = 5 , SHORT_RANGE_RADAR = 6 ,
  LONG_RANGE_RADAR = 7 , MONOCULAR_CAMERA = 8 , STEREO_CAMERA = 9 , ULTRASONIC = 10 ,
  SENSOR_TYPE_NUM
}
 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 更多...
 
enum class  SensorOrientation {
  FRONT = 0 , LEFT_FORWARD = 1 , LEFT = 2 , LEFT_BACKWARD = 3 ,
  REAR = 4 , RIGHT_BACKWARD = 5 , RIGHT = 6 , RIGHT_FORWARD = 7 ,
  PANORAMIC = 8
}
 
enum class  TLColor {
  TL_UNKNOWN_COLOR = 0 , TL_RED = 1 , TL_YELLOW = 2 , TL_GREEN = 3 ,
  TL_BLACK = 4 , TL_TOTAL_COLOR_NUM = 5
}
 
enum class  TLDetectionClass { TL_UNKNOWN_CLASS = -1 , TL_VERTICAL_CLASS = 0 , TL_QUADRATE_CLASS = 1 , TL_HORIZONTAL_CLASS = 2 }
 

函数

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)
 

变量

constexpr size_t kMaxBlobAxes = 32
 
const std::map< Color, int > kChannelsMap
 
struct apollo::perception::base::ImpendingCollisionEdges EIGEN_ALIGN16
 
const std::map< VisualLandmarkType, std::string > kVisualLandmarkType2NameMap
 
const std::map< std::string, base::VisualLandmarkTypekVisualLandmarkName2TypeMap
 
const std::map< ObjectType, std::string > kObjectType2NameMap
 ObjectType mapping
 
const std::map< std::string, ObjectTypekObjectName2TypeMap
 
const std::map< ObjectSemanticType, std::string > kObjectSemanticType2NameMap
 ObjectSemanticType mapping
 
const std::map< std::string, ObjectSemanticTypekName2ObjectSemanticTypeMap
 
const std::map< VisualObjectType, ObjectTypekVisualTypeMap
 VisualObjectType mapping
 
const std::map< VisualObjectType, std::string > kVisualType2NameMap
 
const std::map< std::string, base::VisualObjectTypekVisualName2TypeMap
 
const std::map< ObjectSubType, ObjectTypekSubType2TypeMap
 ObjectSubType mapping
 
const std::map< ObjectSubType, std::string > kSubType2NameMap
 
const std::map< std::string, ObjectSubTypekName2SubTypeMap
 
const std::size_t kDefaultReservePointNum = 50000
 

类型定义说明

◆ BaseCameraModelConstPtr

在文件 camera.h76 行定义.

◆ BaseCameraModelPtr

在文件 camera.h75 行定义.

◆ BBox2DD

在文件 box.h165 行定义.

◆ BBox2DF

在文件 box.h164 行定义.

◆ BBox2DI

在文件 box.h163 行定义.

◆ BlobConstPtr

template<typename Dtype >
using apollo::perception::base::BlobConstPtr = typedef std::shared_ptr<const Blob<Dtype> >

在文件 blob.h315 行定义.

◆ BlobPtr

template<typename Dtype >
using apollo::perception::base::BlobPtr = typedef std::shared_ptr<Blob<Dtype> >

在文件 blob.h313 行定义.

◆ BrownCameraDistortionModelConstPtr

◆ BrownCameraDistortionModelPtr

◆ CameraFrameSupplementConstPtr

◆ CameraFrameSupplementPtr

◆ CameraObjectSupplementConstPtr

◆ CameraObjectSupplementPtr

◆ FrameConstPtr

typedef std::shared_ptr<const Frame> apollo::perception::base::FrameConstPtr

在文件 frame.h61 行定义.

◆ FramePool

在文件 object_pool_types.h72 行定义.

◆ FramePtr

typedef std::shared_ptr<Frame> apollo::perception::base::FramePtr

在文件 frame.h60 行定义.

◆ HdmapStructConstPtr

using apollo::perception::base::HdmapStructConstPtr = typedef std::shared_ptr<const HdmapStruct>

在文件 hdmap_struct.h46 行定义.

◆ HdmapStructPtr

using apollo::perception::base::HdmapStructPtr = typedef std::shared_ptr<HdmapStruct>

在文件 hdmap_struct.h45 行定义.

◆ Image8UConstPtr

typedef std::shared_ptr<const Image8U> apollo::perception::base::Image8UConstPtr

在文件 image_8u.h149 行定义.

◆ Image8UPtr

在文件 image_8u.h148 行定义.

◆ LidarFrameSupplementConstPtr

◆ LidarFrameSupplementPtr

◆ LidarObjectSupplementConstPtr

◆ LidarObjectSupplementPtr

◆ Motion3DBuffer

在文件 object_supplement.h287 行定义.

◆ Motion3DBufferConstPtr

在文件 object_supplement.h289 行定义.

◆ Motion3DBufferPtr

在文件 object_supplement.h288 行定义.

◆ MotionBuffer

typedef boost::circular_buffer<VehicleStatus> apollo::perception::base::MotionBuffer

在文件 object_supplement.h269 行定义.

◆ MotionBufferConstPtr

在文件 object_supplement.h271 行定义.

◆ MotionBufferPtr

在文件 object_supplement.h270 行定义.

◆ MotionType

typedef Eigen::Matrix4f apollo::perception::base::MotionType

在文件 object_supplement.h253 行定义.

◆ ObjectConstPtr

using apollo::perception::base::ObjectConstPtr = typedef std::shared_ptr<const Object>

在文件 object.h128 行定义.

◆ ObjectPool

在文件 object_pool_types.h54 行定义.

◆ ObjectPtr

using apollo::perception::base::ObjectPtr = typedef std::shared_ptr<Object>

在文件 object.h127 行定义.

◆ PinholeCameraModelConstPtr

在文件 camera.h78 行定义.

◆ PinholeCameraModelPtr

在文件 camera.h77 行定义.

◆ Point2DD

在文件 point.h89 行定义.

◆ Point2DF

在文件 point.h87 行定义.

◆ Point2DI

在文件 point.h88 行定义.

◆ Point3DD

在文件 point.h100 行定义.

◆ Point3DF

在文件 point.h98 行定义.

◆ Point3DI

在文件 point.h99 行定义.

◆ PointD

using apollo::perception::base::PointD = typedef Point<double>

在文件 point.h57 行定义.

◆ PointDCloud

◆ PointDCloudConstPtr

在文件 point_cloud.h521 行定义.

◆ PointDCloudPool

◆ PointDCloudPtr

在文件 point_cloud.h520 行定义.

◆ PointF

using apollo::perception::base::PointF = typedef Point<float>

在文件 point.h56 行定义.

◆ PointFCloud

◆ PointFCloudConstPtr

在文件 point_cloud.h518 行定义.

◆ PointFCloudPool

◆ PointFCloudPtr

在文件 point_cloud.h517 行定义.

◆ PointIndicesConstPtr

在文件 point_cloud.h511 行定义.

◆ PointIndicesPtr

在文件 point_cloud.h510 行定义.

◆ PointXYZID

在文件 point.h60 行定义.

◆ PointXYZIF

在文件 point.h59 行定义.

◆ PointXYZITD

在文件 point.h62 行定义.

◆ PointXYZITF

在文件 point.h61 行定义.

◆ PointXYZITHBD

在文件 point.h66 行定义.

◆ PointXYZITHBF

在文件 point.h65 行定义.

◆ PointXYZITHBLD

在文件 point.h68 行定义.

◆ PointXYZITHBLF

在文件 point.h67 行定义.

◆ PointXYZITHD

在文件 point.h64 行定义.

◆ PointXYZITHF

在文件 point.h63 行定义.

◆ PolygonDType

◆ PolygonDTypeConstPtr

在文件 point_cloud.h531 行定义.

◆ PolygonDTypePtr

在文件 point_cloud.h530 行定义.

◆ PolygonFType

◆ PolygonFTypeConstPtr

在文件 point_cloud.h528 行定义.

◆ PolygonFTypePtr

在文件 point_cloud.h527 行定义.

◆ Radar4dObjectSupplementConstPtr

◆ Radar4dObjectSupplementPtr

◆ RadarFrameSupplementConstPtr

◆ RadarFrameSupplementPtr

◆ RadarObjectSupplementConstPtr

◆ RadarObjectSupplementPtr

◆ RadarPointD

在文件 point.h114 行定义.

◆ RadarPointDCloud

◆ RadarPointDCloudConstPtr

在文件 radar_point_cloud.h409 行定义.

◆ RadarPointDCloudPool

◆ RadarPointDCloudPtr

◆ RadarPointF

在文件 point.h113 行定义.

◆ RadarPointFCloud

◆ RadarPointFCloudConstPtr

在文件 radar_point_cloud.h406 行定义.

◆ RadarPointFCloudPool

◆ RadarPointFCloudPtr

◆ RadarPointXYZVRD

在文件 point.h116 行定义.

◆ RadarPointXYZVRF

在文件 point.h115 行定义.

◆ RadarPolygonDType

◆ RadarPolygonDTypeConstPtr

在文件 radar_point_cloud.h419 行定义.

◆ RadarPolygonDTypePtr

◆ RadarPolygonFType

◆ RadarPolygonFTypeConstPtr

在文件 radar_point_cloud.h416 行定义.

◆ RadarPolygonFTypePtr

◆ RectD

在文件 box.h161 行定义.

◆ RectF

在文件 box.h160 行定义.

◆ RectI

在文件 box.h159 行定义.

◆ TestDtypes

typedef ::testing::Types<float, double> apollo::perception::base::TestDtypes

在文件 test_helper.h38 行定义.

◆ TestDtypesAndDevices

typedef ::testing::Types<CPUDevice<float>, CPUDevice<double> > apollo::perception::base::TestDtypesAndDevices

在文件 test_helper.h52 行定义.

◆ TrafficLightPtr

在文件 traffic_light.h88 行定义.

◆ TrafficLightPtrs

在文件 traffic_light.h89 行定义.

◆ UltrasonicFrameSupplementConstPtr

◆ UltrasonicFrameSupplementPtr

枚举类型说明

◆ Color

枚举值
NONE 
GRAY 
RGB 
BGR 

在文件 image_8u.h28 行定义.

28 {
29 NONE = 0x00,
30 GRAY = 0x01,
31 RGB = 0x02,
32 BGR = 0x03,
33};

◆ InternalObjectType

◆ LaneLinePositionType

Definition of the position of a lane marking in respect to the ego lane.

枚举值
CURB_LEFT 
FOURTH_LEFT 
THIRD_LEFT 
ADJACENT_LEFT 

lane marking on the left side next to ego lane

EGO_LEFT 

left lane marking of the ego lane

EGO_CENTER 

center lane marking of the ego lane, changing lane

EGO_RIGHT 

right lane marking of the ego lane

ADJACENT_RIGHT 

lane marking on the right side next to ego lane

THIRD_RIGHT 
FOURTH_RIGHT 
CURB_RIGHT 
OTHER 

other types of lane

UNKNOWN 

background

在文件 lane_struct.h34 行定义.

◆ LaneLineType

枚举值
WHITE_DASHED 
WHITE_SOLID 
YELLOW_DASHED 
YELLOW_SOLID 

在文件 lane_struct.h26 行定义.

◆ LaneLineUseType

◆ MotionState

枚举值
UNKNOWN 
MOVING 
STATIONARY 
MAX_MOTION_STATE 

在文件 object_types.h99 行定义.

99 {
100 UNKNOWN = 0,
101 MOVING = 1,
102 STATIONARY = 2,
104};

◆ ObjectSemanticType

◆ ObjectSubType

枚举值
UNKNOWN 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
CAR 
VAN 
TRUCK 
BUS 
CYCLIST 
MOTORCYCLIST 
TRICYCLIST 
PEDESTRIAN 
TRAFFICCONE 
SMALLMOT 
BIGMOT 
NONMOT 
MAX_OBJECT_TYPE 

在文件 object_types.h77 行定义.

◆ ObjectType

枚举值
UNKNOWN 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
PEDESTRIAN 
BICYCLE 
VEHICLE 
MAX_OBJECT_TYPE 

在文件 object_types.h26 行定义.

◆ SensorOrientation

枚举值
FRONT 
LEFT_FORWARD 
LEFT 
LEFT_BACKWARD 
REAR 
RIGHT_BACKWARD 
RIGHT 
RIGHT_FORWARD 
PANORAMIC 

在文件 sensor_meta.h45 行定义.

◆ SensorType

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.h29 行定义.

◆ TLColor

枚举值
TL_UNKNOWN_COLOR 
TL_RED 
TL_YELLOW 
TL_GREEN 
TL_BLACK 
TL_TOTAL_COLOR_NUM 

在文件 traffic_light.h28 行定义.

◆ TLDetectionClass

枚举值
TL_UNKNOWN_CLASS 
TL_VERTICAL_CLASS 
TL_QUADRATE_CLASS 
TL_HORIZONTAL_CLASS 

在文件 traffic_light.h37 行定义.

◆ VisualLandmarkType

◆ VisualObjectType

枚举值
CAR 
VAN 
BUS 
TRUCK 
BICYCLE 
TRICYCLE 
PEDESTRIAN 
TRAFFICCONE 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
MAX_OBJECT_TYPE 

在文件 object_types.h62 行定义.

函数说明

◆ __attribute__()

apollo::perception::base::__attribute__ ( (constructor)  )

在文件 object_pool_types.cc25 行定义.

25 {
26 ObjectPool::Instance();
27 PointFCloudPool::Instance();
28 PointDCloudPool::Instance();
29 FramePool::Instance();
30#ifndef PERCEPTION_BASE_DISABLE_POOL
31 AINFO << "Initialize base object pool (no-malloc).";
32#else
33 AINFO << "Initialize base object pool (malloc).";
34#endif
35}
#define AINFO
Definition log.h:42

◆ CloudDemean() [1/2]

void apollo::perception::base::CloudDemean ( base::PointFCloudPtr  cloud)

◆ CloudDemean() [2/2]

void apollo::perception::base::CloudDemean ( PointFCloud pc)

在文件 point_cloud_util.cc59 行定义.

59 {
60 // Demean by using centroid.
61 PointF centroid;
62 GetPointCloudCentroid(*pc, &centroid);
63 for (size_t i = 0; i < pc->size(); ++i) {
64 (*pc)[i].x -= centroid.x;
65 (*pc)[i].y -= centroid.y;
66 (*pc)[i].z -= centroid.z;
67 }
68}
void GetPointCloudCentroid(const PointFCloud &cloud, PointF *centroid)

◆ DownSamplePointCloudBeams()

bool apollo::perception::base::DownSamplePointCloudBeams ( base::PointFCloudPtr  cloud_ptr,
base::PointFCloudPtr  out_cloud_ptr,
int  downsample_factor 
)

在文件 point_cloud_util.cc29 行定义.

31 {
32 if (downsample_factor <= 0) {
33 return false;
34 }
35 for (size_t i = 0; i < cloud_ptr->size(); ++i) {
36 int32_t beam_id = cloud_ptr->points_beam_id(i);
37 if (beam_id % downsample_factor == 0) {
38 base::PointF point = cloud_ptr->at(i);
39 double timestamp = cloud_ptr->points_timestamp(i);
40 float height = cloud_ptr->points_height(i);
41 uint8_t label = cloud_ptr->points_label(i);
42 out_cloud_ptr->push_back(point, timestamp, height, beam_id, label);
43 }
44 }
45 return true;
46}

◆ Equal() [1/2]

template<typename T >
std::enable_if< std::is_integral< T >::value, bool >::type apollo::perception::base::Equal ( const T &  lhs,
const T &  rhs 
)

在文件 comparison_traits.h28 行定义.

29 {
30 return lhs == rhs;
31}

◆ Equal() [2/2]

template<typename T >
std::enable_if< std::is_floating_point< T >::value, bool >::type apollo::perception::base::Equal ( const T &  lhs,
const T &  rhs 
)

在文件 comparison_traits.h35 行定义.

36 {
37 return std::fabs(lhs - rhs) < std::numeric_limits<T>::epsilon();
38}

◆ GetMaxScoreIndex()

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 
)

在文件 nms.h30 行定义.

32 {
33 ACHECK(score_index_vec != nullptr);
34
35 for (size_t i = 0; i < scores.size(); ++i) {
36 if (scores[i] > threshold) {
37 score_index_vec->emplace_back(scores[i], i);
38 }
39 }
40
41 std::sort(score_index_vec->begin(), score_index_vec->end(),
42 [](const std::pair<float, int> &a, const std::pair<float, int> &b) {
43 return a.first > b.first;
44 });
45
46 if (top_k > 0 && top_k < static_cast<int>(score_index_vec->size())) {
47 score_index_vec->resize(top_k);
48 }
49}
#define ACHECK(cond)
Definition log.h:80

◆ GetPointCloudCentroid() [1/2]

void apollo::perception::base::GetPointCloudCentroid ( base::PointFCloudConstPtr  cloud,
PointF centroid 
)

◆ GetPointCloudCentroid() [2/2]

void apollo::perception::base::GetPointCloudCentroid ( const PointFCloud cloud,
PointF centroid 
)

在文件 point_cloud_util.cc48 行定义.

48 {
49 for (size_t i = 0; i < cloud.size(); ++i) {
50 centroid->x += cloud[i].x;
51 centroid->y += cloud[i].y;
52 centroid->z += cloud[i].z;
53 }
54 centroid->x /= static_cast<float>(cloud.size());
55 centroid->y /= static_cast<float>(cloud.size());
56 centroid->z /= static_cast<float>(cloud.size());
57}

◆ GetPointCloudMinareaBbox()

bool apollo::perception::base::GetPointCloudMinareaBbox ( const PointFCloud pc,
BoundingCube box,
const int &  min_num_points,
const bool &  verbose 
)

在文件 point_cloud_util.cc93 行定义.

94 {
95 if (pc.size() <= static_cast<size_t>(min_num_points)) {
96 return false;
97 }
98 std::vector<cv::Point2f> pts;
99 float min_z = std::numeric_limits<float>::max();
100 float max_z = -std::numeric_limits<float>::max();
101 for (size_t i = 0; i < pc.size(); ++i) {
102 pts.push_back(cv::Point2f(pc[i].x, pc[i].y));
103 min_z = std::min(min_z, pc[i].z);
104 max_z = std::max(max_z, pc[i].z);
105 }
106 // compute MinAreaRect
107 cv::RotatedRect mar = cv::minAreaRect(pts);
108 // adjust angle
109 if (mar.size.width < mar.size.height) {
110 mar.angle -= 90;
111 float tmp = mar.size.width;
112 mar.size.width = mar.size.height;
113 mar.size.height = tmp;
114 }
115 if (verbose) {
116 AINFO << "center = " << mar.center.x << " " << mar.center.y << std::endl;
117 AINFO << "size = " << mar.size.height << " " << mar.size.width << std::endl;
118 AINFO << "yaw = " << mar.angle << std::endl;
119 AINFO << "height = " << max_z - min_z << std::endl;
120 }
121 box->x = mar.center.x;
122 box->y = mar.center.y;
123 box->z = static_cast<float>((min_z + max_z) / 2.0);
124 box->length = mar.size.width;
125 box->width = mar.size.height;
126 box->height = max_z - min_z;
127 box->yaw = static_cast<float>((M_PI * (mar.angle + 180)) / 180);
128 return true;
129}

◆ Nms()

template<typename BoxType >
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 
)

在文件 nms.h52 行定义.

56 {
57 ACHECK(bboxes.size() == scores.size());
58 ACHECK(indices != nullptr);
59
60 std::vector<std::pair<float, int>> score_index_vec;
61 GetMaxScoreIndex(scores, score_threshold, top_k, &score_index_vec);
62
63 float adaptive_threshold = nms_threshold;
64 indices->clear();
65 for (const std::pair<float, int> &score_index : score_index_vec) {
66 const int idx = score_index.second;
67 bool keep = true;
68 for (const int &kept_idx : *indices) {
69 float overlap = ComputeOverlap(bboxes[idx], bboxes[kept_idx]);
70 if (overlap > adaptive_threshold) {
71 keep = false;
72 break;
73 }
74 }
75
76 if (keep) {
77 indices->push_back(idx);
78 if (static_cast<int>(indices->size()) >= limit) {
79 break;
80 }
81 }
82
83 if (keep && eta < 1 && adaptive_threshold > 0.5) {
84 adaptive_threshold *= eta;
85 }
86 }
87}
void GetMaxScoreIndex(const std::vector< float > &scores, const float threshold, const int top_k, std::vector< std::pair< float, int > > *score_index_vec)
Definition nms.h:30

◆ operator<<()

std::ostream & apollo::perception::base::operator<< ( std::ostream &  o,
const Polynomial p 
)

在文件 polynomial.cc71 行定义.

71 {
72 const std::map<uint32_t, double>& coeff = p.getCoeff();
73 size_t i = 0;
74 const size_t coeff_num = coeff.size();
75 for (auto it = coeff.rbegin(); it != coeff.rend(); ++it) {
76 const uint32_t order = it->first;
77 const double c = it->second;
78
79 o << "(" << c << ")*(t^" << order << ")";
80 if (i < coeff_num - 1) {
81 o << " + ";
82 }
83 ++i;
84 }
85 return o;
86}
const std::map< uint32_t, double > & getCoeff() const
Definition polynomial.cc:25

◆ OrientCloud()

double apollo::perception::base::OrientCloud ( const PointFCloud pc,
PointFCloud pc_out,
bool  demean 
)

在文件 point_cloud_util.cc70 行定义.

70 {
71 // Approach#1:
72 // Find car dominant direction on XY plane.
73 /*Eigen::VectorXf coeff;
74 find_dominant_direction_xy(pc, coeff);
75 // This theta has ambiguity. To calculate the true heading,
76 // we need to consider both obstacle's velocity direction and
77 // robot's current velocity direction.
78 double theta = atan2(coeff[4], coeff[3]);*/
79 // Approach#2:
80 // Use Minimum Area Bounding Box
81 BoundingCube bbox;
82 GetPointCloudMinareaBbox(pc, &bbox);
83 float theta = static_cast<float>(bbox.yaw);
84 Eigen::Affine3f transform = Eigen::Affine3f::Identity();
85 transform.rotate(Eigen::AngleAxisf(-theta, Eigen::Vector3f(0, 0, 1)));
86 pc.TransformPointCloud(transform, pc_out, true);
87 if (demean) {
88 CloudDemean(pc_out);
89 }
90 return theta;
91}
void TransformPointCloud(bool check_nan=false)
void CloudDemean(PointFCloud *pc)
bool GetPointCloudMinareaBbox(const PointFCloud &pc, BoundingCube *box, const int &min_num_points, const bool &verbose)

◆ PerceptionFreeHost()

void apollo::perception::base::PerceptionFreeHost ( void *  ptr,
bool  use_cuda 
)
inline

在文件 syncedmem.h83 行定义.

83 {
84#if USE_GPU == 1
85 if (use_cuda) {
86 BASE_GPU_CHECK(cudaFreeHost(ptr));
87 return;
88 }
89#endif
90 free(ptr);
91}

◆ PerceptionMallocHost()

void apollo::perception::base::PerceptionMallocHost ( void **  ptr,
size_t  size,
bool  use_cuda 
)
inline

在文件 syncedmem.h72 行定义.

72 {
73#if USE_GPU == 1
74 if (use_cuda) {
75 BASE_GPU_CHECK(cudaMallocHost(ptr, size));
76 return;
77 }
78#endif
79 *ptr = malloc(size);
80 ACHECK(*ptr) << "host allocation of size " << size << " failed";
81}

变量说明

◆ EIGEN_ALIGN16

struct apollo::perception::base::ImpendingCollisionEdges apollo::perception::base::EIGEN_ALIGN16

◆ kChannelsMap

const std::map<Color, int> apollo::perception::base::kChannelsMap
初始值:
{
{Color::GRAY, 1}, {Color::RGB, 3}, {Color::BGR, 3}}

在文件 image_8u.h35 行定义.

35 {
36 {Color::GRAY, 1}, {Color::RGB, 3}, {Color::BGR, 3}};

◆ kDefaultReservePointNum

const std::size_t apollo::perception::base::kDefaultReservePointNum = 50000

在文件 point.h70 行定义.

◆ kMaxBlobAxes

constexpr size_t apollo::perception::base::kMaxBlobAxes = 32
constexpr

在文件 blob.h79 行定义.

◆ kName2ObjectSemanticTypeMap

const std::map<std::string, ObjectSemanticType> apollo::perception::base::kName2ObjectSemanticTypeMap
初始值:
= {
{"UNKNOWN", ObjectSemanticType::UNKNOWN},
{"IGNORE", ObjectSemanticType::IGNORE},
{"GROUND", ObjectSemanticType::GROUND},
{"OBJECT", ObjectSemanticType::OBJECT},
{"CURB", ObjectSemanticType::CURB},
{"VEGETATION", ObjectSemanticType::VEGETATION},
{"FENCE", ObjectSemanticType::FENCE},
{"NOISE", ObjectSemanticType::NOISE},
{"WALL", ObjectSemanticType::WALL},
{"MAX_OBJECT_SEMANTIC_LABEL",
ObjectSemanticType::MAX_OBJECT_SEMANTIC_LABEL}}

在文件 object_types.h169 行定义.

169 {
170 {"UNKNOWN", ObjectSemanticType::UNKNOWN},
171 {"IGNORE", ObjectSemanticType::IGNORE},
172 {"GROUND", ObjectSemanticType::GROUND},
173 {"OBJECT", ObjectSemanticType::OBJECT},
174 {"CURB", ObjectSemanticType::CURB},
175 {"VEGETATION", ObjectSemanticType::VEGETATION},
176 {"FENCE", ObjectSemanticType::FENCE},
177 {"NOISE", ObjectSemanticType::NOISE},
178 {"WALL", ObjectSemanticType::WALL},
179 {"MAX_OBJECT_SEMANTIC_LABEL",
180 ObjectSemanticType::MAX_OBJECT_SEMANTIC_LABEL}};

◆ kName2SubTypeMap

const std::map<std::string, ObjectSubType> apollo::perception::base::kName2SubTypeMap
初始值:
= {
{"UNKNOWN", ObjectSubType::UNKNOWN},
{"UNKNOWN_MOVABLE", ObjectSubType::UNKNOWN_MOVABLE},
{"UNKNOWN_UNMOVABLE", ObjectSubType::UNKNOWN_UNMOVABLE},
{"CAR", ObjectSubType::CAR},
{"VAN", ObjectSubType::VAN},
{"TRUCK", ObjectSubType::TRUCK},
{"BUS", ObjectSubType::BUS},
{"CYCLIST", ObjectSubType::CYCLIST},
{"MOTORCYCLIST", ObjectSubType::MOTORCYCLIST},
{"TRICYCLIST", ObjectSubType::TRICYCLIST},
{"PEDESTRIAN", ObjectSubType::PEDESTRIAN},
{"TRAFFICCONE", ObjectSubType::TRAFFICCONE},
{"MAX_OBJECT_TYPE", ObjectSubType::MAX_OBJECT_TYPE},
}

在文件 object_types.h265 行定义.

265 {
266 {"UNKNOWN", ObjectSubType::UNKNOWN},
267 {"UNKNOWN_MOVABLE", ObjectSubType::UNKNOWN_MOVABLE},
268 {"UNKNOWN_UNMOVABLE", ObjectSubType::UNKNOWN_UNMOVABLE},
269 {"CAR", ObjectSubType::CAR},
270 {"VAN", ObjectSubType::VAN},
271 {"TRUCK", ObjectSubType::TRUCK},
272 {"BUS", ObjectSubType::BUS},
273 {"CYCLIST", ObjectSubType::CYCLIST},
274 {"MOTORCYCLIST", ObjectSubType::MOTORCYCLIST},
275 {"TRICYCLIST", ObjectSubType::TRICYCLIST},
276 {"PEDESTRIAN", ObjectSubType::PEDESTRIAN},
277 {"TRAFFICCONE", ObjectSubType::TRAFFICCONE},
278 {"MAX_OBJECT_TYPE", ObjectSubType::MAX_OBJECT_TYPE},
279};

◆ kObjectName2TypeMap

const std::map<std::string, ObjectType> apollo::perception::base::kObjectName2TypeMap
初始值:
= {
{"UNKNOWN", ObjectType::UNKNOWN},
{"UNKNOWN_MOVABLE", ObjectType::UNKNOWN_MOVABLE},
{"UNKNOWN_UNMOVABLE", ObjectType::UNKNOWN_UNMOVABLE},
{"PEDESTRIAN", ObjectType::PEDESTRIAN},
{"BICYCLE", ObjectType::BICYCLE},
{"VEHICLE", ObjectType::VEHICLE},
{"MAX_OBJECT_TYPE", ObjectType::MAX_OBJECT_TYPE}}

在文件 object_types.h144 行定义.

144 {
145 {"UNKNOWN", ObjectType::UNKNOWN},
146 {"UNKNOWN_MOVABLE", ObjectType::UNKNOWN_MOVABLE},
147 {"UNKNOWN_UNMOVABLE", ObjectType::UNKNOWN_UNMOVABLE},
148 {"PEDESTRIAN", ObjectType::PEDESTRIAN},
149 {"BICYCLE", ObjectType::BICYCLE},
150 {"VEHICLE", ObjectType::VEHICLE},
151 {"MAX_OBJECT_TYPE", ObjectType::MAX_OBJECT_TYPE}};

◆ kObjectSemanticType2NameMap

const std::map<ObjectSemanticType, std::string> apollo::perception::base::kObjectSemanticType2NameMap
初始值:
= {
{ObjectSemanticType::UNKNOWN, "UNKNOWN"},
{ObjectSemanticType::IGNORE, "IGNORE"},
{ObjectSemanticType::GROUND, "GROUND"},
{ObjectSemanticType::OBJECT, "OBJECT"},
{ObjectSemanticType::CURB, "CURB"},
{ObjectSemanticType::VEGETATION, "VEGETATION"},
{ObjectSemanticType::FENCE, "FENCE"},
{ObjectSemanticType::NOISE, "NOISE"},
{ObjectSemanticType::WALL, "WALL"},
{ObjectSemanticType::MAX_OBJECT_SEMANTIC_LABEL,
"MAX_OBJECT_SEMANTIC_LABEL"}}

ObjectSemanticType mapping

在文件 object_types.h156 行定义.

156 {
157 {ObjectSemanticType::UNKNOWN, "UNKNOWN"},
158 {ObjectSemanticType::IGNORE, "IGNORE"},
159 {ObjectSemanticType::GROUND, "GROUND"},
160 {ObjectSemanticType::OBJECT, "OBJECT"},
161 {ObjectSemanticType::CURB, "CURB"},
162 {ObjectSemanticType::VEGETATION, "VEGETATION"},
163 {ObjectSemanticType::FENCE, "FENCE"},
164 {ObjectSemanticType::NOISE, "NOISE"},
165 {ObjectSemanticType::WALL, "WALL"},
166 {ObjectSemanticType::MAX_OBJECT_SEMANTIC_LABEL,
167 "MAX_OBJECT_SEMANTIC_LABEL"}};

◆ kObjectType2NameMap

const std::map<ObjectType, std::string> apollo::perception::base::kObjectType2NameMap
初始值:
= {
{ObjectType::UNKNOWN, "UNKNOWN"},
{ObjectType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
{ObjectType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
{ObjectType::PEDESTRIAN, "PEDESTRIAN"},
{ObjectType::BICYCLE, "BICYCLE"},
{ObjectType::VEHICLE, "VEHICLE"},
{ObjectType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"}}

ObjectType mapping

在文件 object_types.h135 行定义.

135 {
136 {ObjectType::UNKNOWN, "UNKNOWN"},
137 {ObjectType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
138 {ObjectType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
139 {ObjectType::PEDESTRIAN, "PEDESTRIAN"},
140 {ObjectType::BICYCLE, "BICYCLE"},
141 {ObjectType::VEHICLE, "VEHICLE"},
142 {ObjectType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"}};

◆ kSubType2NameMap

const std::map<ObjectSubType, std::string> apollo::perception::base::kSubType2NameMap
初始值:
= {
{ObjectSubType::UNKNOWN, "UNKNOWN"},
{ObjectSubType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
{ObjectSubType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
{ObjectSubType::CAR, "CAR"},
{ObjectSubType::VAN, "VAN"},
{ObjectSubType::TRUCK, "TRUCK"},
{ObjectSubType::BUS, "BUS"},
{ObjectSubType::CYCLIST, "CYCLIST"},
{ObjectSubType::MOTORCYCLIST, "MOTORCYCLIST"},
{ObjectSubType::TRICYCLIST, "TRICYCLIST"},
{ObjectSubType::PEDESTRIAN, "PEDESTRIAN"},
{ObjectSubType::TRAFFICCONE, "TRAFFICCONE"},
{ObjectSubType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"},
}

在文件 object_types.h249 行定义.

249 {
250 {ObjectSubType::UNKNOWN, "UNKNOWN"},
251 {ObjectSubType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
252 {ObjectSubType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
253 {ObjectSubType::CAR, "CAR"},
254 {ObjectSubType::VAN, "VAN"},
255 {ObjectSubType::TRUCK, "TRUCK"},
256 {ObjectSubType::BUS, "BUS"},
257 {ObjectSubType::CYCLIST, "CYCLIST"},
258 {ObjectSubType::MOTORCYCLIST, "MOTORCYCLIST"},
259 {ObjectSubType::TRICYCLIST, "TRICYCLIST"},
260 {ObjectSubType::PEDESTRIAN, "PEDESTRIAN"},
261 {ObjectSubType::TRAFFICCONE, "TRAFFICCONE"},
262 {ObjectSubType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"},
263};

◆ kSubType2TypeMap

const std::map<ObjectSubType, ObjectType> apollo::perception::base::kSubType2TypeMap
初始值:
= {
{ObjectSubType::UNKNOWN, ObjectType::UNKNOWN},
{ObjectSubType::UNKNOWN_MOVABLE, ObjectType::UNKNOWN_MOVABLE},
{ObjectSubType::UNKNOWN_UNMOVABLE, ObjectType::UNKNOWN_UNMOVABLE},
{ObjectSubType::CAR, ObjectType::VEHICLE},
{ObjectSubType::VAN, ObjectType::VEHICLE},
{ObjectSubType::TRUCK, ObjectType::VEHICLE},
{ObjectSubType::BUS, ObjectType::VEHICLE},
{ObjectSubType::CYCLIST, ObjectType::BICYCLE},
{ObjectSubType::MOTORCYCLIST, ObjectType::BICYCLE},
{ObjectSubType::TRICYCLIST, ObjectType::BICYCLE},
{ObjectSubType::PEDESTRIAN, ObjectType::PEDESTRIAN},
{ObjectSubType::SMALLMOT, ObjectType::VEHICLE},
{ObjectSubType::BIGMOT, ObjectType::VEHICLE},
{ObjectSubType::NONMOT, ObjectType::BICYCLE},
{ObjectSubType::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
{ObjectSubType::MAX_OBJECT_TYPE, ObjectType::MAX_OBJECT_TYPE},
}

ObjectSubType mapping

在文件 object_types.h230 行定义.

230 {
231 {ObjectSubType::UNKNOWN, ObjectType::UNKNOWN},
232 {ObjectSubType::UNKNOWN_MOVABLE, ObjectType::UNKNOWN_MOVABLE},
233 {ObjectSubType::UNKNOWN_UNMOVABLE, ObjectType::UNKNOWN_UNMOVABLE},
234 {ObjectSubType::CAR, ObjectType::VEHICLE},
235 {ObjectSubType::VAN, ObjectType::VEHICLE},
236 {ObjectSubType::TRUCK, ObjectType::VEHICLE},
237 {ObjectSubType::BUS, ObjectType::VEHICLE},
238 {ObjectSubType::CYCLIST, ObjectType::BICYCLE},
239 {ObjectSubType::MOTORCYCLIST, ObjectType::BICYCLE},
240 {ObjectSubType::TRICYCLIST, ObjectType::BICYCLE},
241 {ObjectSubType::PEDESTRIAN, ObjectType::PEDESTRIAN},
242 {ObjectSubType::SMALLMOT, ObjectType::VEHICLE},
243 {ObjectSubType::BIGMOT, ObjectType::VEHICLE},
244 {ObjectSubType::NONMOT, ObjectType::BICYCLE},
245 {ObjectSubType::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
246 {ObjectSubType::MAX_OBJECT_TYPE, ObjectType::MAX_OBJECT_TYPE},
247};

◆ kVisualLandmarkName2TypeMap

const std::map<std::string, base::VisualLandmarkType> apollo::perception::base::kVisualLandmarkName2TypeMap
初始值:
= {
{"RoadArrow", VisualLandmarkType::RoadArrow},
{"RoadText", VisualLandmarkType::RoadText},
{"TrafficSign", VisualLandmarkType::TrafficSign},
{"TrafficLight", VisualLandmarkType::TrafficLight},
}

在文件 object_types.h125 行定义.

125 {
126 {"RoadArrow", VisualLandmarkType::RoadArrow},
127 {"RoadText", VisualLandmarkType::RoadText},
128 {"TrafficSign", VisualLandmarkType::TrafficSign},
129 {"TrafficLight", VisualLandmarkType::TrafficLight},
130};

◆ kVisualLandmarkType2NameMap

const std::map<VisualLandmarkType, std::string> apollo::perception::base::kVisualLandmarkType2NameMap
初始值:
= {
{VisualLandmarkType::RoadArrow, "RoadArrow"},
{VisualLandmarkType::RoadText, "RoadText"},
{VisualLandmarkType::TrafficSign, "TrafficSign"},
{VisualLandmarkType::TrafficLight, "TrafficLight"},
}

在文件 object_types.h117 行定义.

117 {
118 {VisualLandmarkType::RoadArrow, "RoadArrow"},
119 {VisualLandmarkType::RoadText, "RoadText"},
120 {VisualLandmarkType::TrafficSign, "TrafficSign"},
121 {VisualLandmarkType::TrafficLight, "TrafficLight"},
122};

◆ kVisualName2TypeMap

const std::map<std::string, base::VisualObjectType> apollo::perception::base::kVisualName2TypeMap
初始值:
= {
{"CAR", VisualObjectType::CAR},
{"VAN", VisualObjectType::VAN},
{"BUS", VisualObjectType::BUS},
{"TRUCK", VisualObjectType::TRUCK},
{"BICYCLE", VisualObjectType::BICYCLE},
{"TRICYCLE", VisualObjectType::TRICYCLE},
{"PEDESTRIAN", VisualObjectType::PEDESTRIAN},
{"TRAFFICCONE", VisualObjectType::TRAFFICCONE},
{"UNKNOWN_MOVABLE", VisualObjectType::UNKNOWN_MOVABLE},
{"UNKNOWN_UNMOVABLE", VisualObjectType::UNKNOWN_UNMOVABLE},
{"MAX_OBJECT_TYPE", VisualObjectType::MAX_OBJECT_TYPE},
}

在文件 object_types.h213 行定义.

213 {
214 {"CAR", VisualObjectType::CAR},
215 {"VAN", VisualObjectType::VAN},
216 {"BUS", VisualObjectType::BUS},
217 {"TRUCK", VisualObjectType::TRUCK},
218 {"BICYCLE", VisualObjectType::BICYCLE},
219 {"TRICYCLE", VisualObjectType::TRICYCLE},
220 {"PEDESTRIAN", VisualObjectType::PEDESTRIAN},
221 {"TRAFFICCONE", VisualObjectType::TRAFFICCONE},
222 {"UNKNOWN_MOVABLE", VisualObjectType::UNKNOWN_MOVABLE},
223 {"UNKNOWN_UNMOVABLE", VisualObjectType::UNKNOWN_UNMOVABLE},
224 {"MAX_OBJECT_TYPE", VisualObjectType::MAX_OBJECT_TYPE},
225};

◆ kVisualType2NameMap

const std::map<VisualObjectType, std::string> apollo::perception::base::kVisualType2NameMap
初始值:
= {
{VisualObjectType::CAR, "CAR"},
{VisualObjectType::VAN, "VAN"},
{VisualObjectType::BUS, "BUS"},
{VisualObjectType::TRUCK, "TRUCK"},
{VisualObjectType::BICYCLE, "BICYCLE"},
{VisualObjectType::TRICYCLE, "TRICYCLE"},
{VisualObjectType::PEDESTRIAN, "PEDESTRIAN"},
{VisualObjectType::TRAFFICCONE, "TRAFFICCONE"},
{VisualObjectType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
{VisualObjectType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
{VisualObjectType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"},
}

在文件 object_types.h199 行定义.

199 {
200 {VisualObjectType::CAR, "CAR"},
201 {VisualObjectType::VAN, "VAN"},
202 {VisualObjectType::BUS, "BUS"},
203 {VisualObjectType::TRUCK, "TRUCK"},
204 {VisualObjectType::BICYCLE, "BICYCLE"},
205 {VisualObjectType::TRICYCLE, "TRICYCLE"},
206 {VisualObjectType::PEDESTRIAN, "PEDESTRIAN"},
207 {VisualObjectType::TRAFFICCONE, "TRAFFICCONE"},
208 {VisualObjectType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
209 {VisualObjectType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
210 {VisualObjectType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"},
211};

◆ kVisualTypeMap

const std::map<VisualObjectType, ObjectType> apollo::perception::base::kVisualTypeMap
初始值:
= {
{VisualObjectType::CAR, ObjectType::VEHICLE},
{VisualObjectType::VAN, ObjectType::VEHICLE},
{VisualObjectType::BUS, ObjectType::VEHICLE},
{VisualObjectType::TRUCK, ObjectType::VEHICLE},
{VisualObjectType::BICYCLE, ObjectType::BICYCLE},
{VisualObjectType::TRICYCLE, ObjectType::BICYCLE},
{VisualObjectType::PEDESTRIAN, ObjectType::PEDESTRIAN},
{VisualObjectType::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
{VisualObjectType::UNKNOWN_MOVABLE, ObjectType::UNKNOWN_MOVABLE},
{VisualObjectType::UNKNOWN_UNMOVABLE, ObjectType::UNKNOWN_UNMOVABLE},
{VisualObjectType::MAX_OBJECT_TYPE, ObjectType::MAX_OBJECT_TYPE},
}

VisualObjectType mapping

在文件 object_types.h185 行定义.

185 {
186 {VisualObjectType::CAR, ObjectType::VEHICLE},
187 {VisualObjectType::VAN, ObjectType::VEHICLE},
188 {VisualObjectType::BUS, ObjectType::VEHICLE},
189 {VisualObjectType::TRUCK, ObjectType::VEHICLE},
190 {VisualObjectType::BICYCLE, ObjectType::BICYCLE},
191 {VisualObjectType::TRICYCLE, ObjectType::BICYCLE},
192 {VisualObjectType::PEDESTRIAN, ObjectType::PEDESTRIAN},
193 {VisualObjectType::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
194 {VisualObjectType::UNKNOWN_MOVABLE, ObjectType::UNKNOWN_MOVABLE},
195 {VisualObjectType::UNKNOWN_UNMOVABLE, ObjectType::UNKNOWN_UNMOVABLE},
196 {VisualObjectType::MAX_OBJECT_TYPE, ObjectType::MAX_OBJECT_TYPE},
197};