Apollo  6.0
Open source self driving car software
Classes | Typedefs | Enumerations | Functions | Variables
apollo::perception::base Namespace Reference

Classes

class  AttributePointCloud
 
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. More...
 
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. More...
 
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  RadarFrameSupplement
 
struct  RadarObjectSupplement
 
struct  Rect
 
struct  RoadBoundary
 
struct  SensorInfo
 
struct  SensorObjectMeasurement
 
class  SyncedMemory
 Manages memory allocation and synchronization between the host (CPU) and device (GPU). More...
 
struct  TrafficLight
 
struct  UltrasonicFrameSupplement
 
struct  Vehicle3DStatus
 
struct  VehicleStatus
 

Typedefs

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 FramePool = ConcurrentObjectPool< Frame, kFramePoolSize, FrameInitializer >
 
typedef std::shared_ptr< LidarObjectSupplementLidarObjectSupplementPtr
 
typedef std::shared_ptr< const LidarObjectSupplementLidarObjectSupplementConstPtr
 
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 >
 
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 ::testing::Types< float, double > TestDtypes
 
typedef ::testing::Types< CPUDevice< float >, CPUDevice< double > > TestDtypesAndDevices
 
typedef std::shared_ptr< TrafficLightTrafficLightPtr
 
typedef std::vector< TrafficLightPtrTrafficLightPtrs
 

Enumerations

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

Functions

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)
 
bool DownSamplePointCloudBeams (base::PointFCloudPtr cloud_ptr, base::PointFCloudPtr out_cloud_ptr, int downsample_factor)
 
bool GetPointCloudMinareaBbox (const base::PointFCloud &pc, BoundingCube *box, const int &min_num_points=5, const bool &verbose=false)
 
void CloudDemean (base::PointFCloudPtr cloud)
 
void GetPointCloudCentroid (base::PointFCloudConstPtr cloud, PointF *centroid)
 
double OrientCloud (const PointFCloud &pc, PointFCloud *pc_out, bool demean)
 
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)
 

Variables

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
 
const std::map< std::string, ObjectTypekObjectName2TypeMap
 
const std::map< VisualObjectType, ObjectTypekVisualTypeMap
 
const std::map< VisualObjectType, std::string > kVisualType2NameMap
 
const std::map< std::string, base::VisualObjectTypekVisualName2TypeMap
 
const std::map< ObjectSubType, ObjectTypekSubType2TypeMap
 
const std::map< ObjectSubType, std::string > kSubType2NameMap
 
const std::map< std::string, ObjectSubTypekName2SubTypeMap
 
const std::size_t kDefaultReservePointNum = 50000
 

Typedef Documentation

◆ BaseCameraModelConstPtr

◆ BaseCameraModelPtr

◆ BBox2DD

◆ BBox2DF

◆ BBox2DI

◆ BlobConstPtr

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

◆ BlobPtr

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

◆ BrownCameraDistortionModelConstPtr

◆ BrownCameraDistortionModelPtr

◆ CameraFrameSupplementConstPtr

◆ CameraFrameSupplementPtr

◆ CameraObjectSupplementConstPtr

◆ CameraObjectSupplementPtr

◆ FrameConstPtr

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

◆ FramePool

◆ FramePtr

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

◆ HdmapStructConstPtr

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

◆ HdmapStructPtr

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

◆ Image8UConstPtr

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

◆ Image8UPtr

◆ LidarFrameSupplementConstPtr

◆ LidarFrameSupplementPtr

◆ LidarObjectSupplementConstPtr

◆ LidarObjectSupplementPtr

◆ Motion3DBuffer

◆ Motion3DBufferConstPtr

◆ Motion3DBufferPtr

◆ MotionBuffer

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

◆ MotionBufferConstPtr

◆ MotionBufferPtr

◆ MotionType

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

◆ ObjectConstPtr

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

◆ ObjectPool

◆ ObjectPtr

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

◆ PinholeCameraModelConstPtr

◆ PinholeCameraModelPtr

◆ Point2DD

◆ Point2DF

◆ Point2DI

◆ Point3DD

◆ Point3DF

◆ Point3DI

◆ PointD

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

◆ PointDCloud

◆ PointDCloudConstPtr

◆ PointDCloudPool

◆ PointDCloudPtr

◆ PointF

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

◆ PointFCloud

◆ PointFCloudConstPtr

◆ PointFCloudPool

◆ PointFCloudPtr

◆ PointIndicesConstPtr

◆ PointIndicesPtr

◆ PointXYZID

◆ PointXYZIF

◆ PointXYZITD

◆ PointXYZITF

◆ PointXYZITHBD

◆ PointXYZITHBF

◆ PointXYZITHBLD

◆ PointXYZITHBLF

◆ PointXYZITHD

◆ PointXYZITHF

◆ PolygonDType

◆ PolygonDTypeConstPtr

◆ PolygonDTypePtr

◆ PolygonFType

◆ PolygonFTypeConstPtr

◆ PolygonFTypePtr

◆ RadarFrameSupplementConstPtr

◆ RadarFrameSupplementPtr

◆ RadarObjectSupplementConstPtr

◆ RadarObjectSupplementPtr

◆ RectD

◆ RectF

◆ RectI

◆ TestDtypes

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

◆ TestDtypesAndDevices

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

◆ TrafficLightPtr

◆ TrafficLightPtrs

◆ UltrasonicFrameSupplementConstPtr

◆ UltrasonicFrameSupplementPtr

Enumeration Type Documentation

◆ Color

Enumerator
NONE 
GRAY 
RGB 
BGR 

◆ InternalObjectType

Enumerator
INT_BACKGROUND 
INT_SMALLMOT 
INT_PEDESTRIAN 
INT_NONMOT 
INT_BIGMOT 
INT_UNKNOWN 
INT_MAX_OBJECT_TYPE 

◆ LaneLinePositionType

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

Enumerator
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

◆ LaneLineType

Enumerator
WHITE_DASHED 
WHITE_SOLID 
YELLOW_DASHED 
YELLOW_SOLID 

◆ LaneLineUseType

Enumerator
REAL 
VIRTUAL 

◆ MotionState

Enumerator
UNKNOWN 
MOVING 
STATIONARY 

◆ ObjectSubType

Enumerator
UNKNOWN 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
CAR 
VAN 
TRUCK 
BUS 
CYCLIST 
MOTORCYCLIST 
TRICYCLIST 
PEDESTRIAN 
TRAFFICCONE 
MAX_OBJECT_TYPE 

◆ ObjectType

Enumerator
UNKNOWN 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
PEDESTRIAN 
BICYCLE 
VEHICLE 
MAX_OBJECT_TYPE 

◆ SensorOrientation

Enumerator
FRONT 
LEFT_FORWARD 
LEFT 
LEFT_BACKWARD 
REAR 
RIGHT_BACKWARD 
RIGHT 
RIGHT_FORWARD 
PANORAMIC 

◆ 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.

Enumerator
UNKNOWN_SENSOR_TYPE 
VELODYNE_64 
VELODYNE_32 
VELODYNE_16 
LDLIDAR_4 
LDLIDAR_1 
SHORT_RANGE_RADAR 
LONG_RANGE_RADAR 
MONOCULAR_CAMERA 
STEREO_CAMERA 
ULTRASONIC 
VELODYNE_128 
SENSOR_TYPE_NUM 

◆ TLColor

Enumerator
TL_UNKNOWN_COLOR 
TL_RED 
TL_YELLOW 
TL_GREEN 
TL_BLACK 
TL_TOTAL_COLOR_NUM 

◆ TLDetectionClass

Enumerator
TL_UNKNOWN_CLASS 
TL_VERTICAL_CLASS 
TL_QUADRATE_CLASS 
TL_HORIZONTAL_CLASS 

◆ VisualLandmarkType

Landmark types and mapping

Enumerator
RoadArrow 
RoadText 
TrafficSign 
TrafficLight 
MAX_LANDMARK_TYPE 

◆ VisualObjectType

Enumerator
CAR 
VAN 
BUS 
TRUCK 
BICYCLE 
TRICYCLE 
PEDESTRIAN 
TRAFFICCONE 
UNKNOWN_MOVABLE 
UNKNOWN_UNMOVABLE 
MAX_OBJECT_TYPE 

Function Documentation

◆ CloudDemean()

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

◆ DownSamplePointCloudBeams()

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

◆ 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 
)

◆ 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 
)

◆ GetPointCloudCentroid()

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

◆ GetPointCloudMinareaBbox()

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

◆ operator<<()

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

◆ OrientCloud()

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

◆ PerceptionFreeHost()

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

◆ PerceptionMallocHost()

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

Variable Documentation

◆ EIGEN_ALIGN16

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

◆ kChannelsMap

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

◆ kDefaultReservePointNum

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

◆ kMaxBlobAxes

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

◆ kName2SubTypeMap

const std::map<std::string, ObjectSubType> apollo::perception::base::kName2SubTypeMap
Initial value:
= {
{"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},
}

◆ kObjectName2TypeMap

const std::map<std::string, ObjectType> apollo::perception::base::kObjectName2TypeMap
Initial value:
= {
{"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}}

◆ kObjectType2NameMap

const std::map<ObjectType, std::string> apollo::perception::base::kObjectType2NameMap
Initial value:
= {
{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

◆ kSubType2NameMap

const std::map<ObjectSubType, std::string> apollo::perception::base::kSubType2NameMap
Initial value:
= {
{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"},
}

◆ kSubType2TypeMap

const std::map<ObjectSubType, ObjectType> apollo::perception::base::kSubType2TypeMap
Initial value:
= {
{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::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
}

ObjectSubType mapping

◆ kVisualLandmarkName2TypeMap

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

◆ kVisualLandmarkType2NameMap

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

◆ kVisualName2TypeMap

const std::map<std::string, base::VisualObjectType> apollo::perception::base::kVisualName2TypeMap
Initial value:
= {
{"CAR", VisualObjectType::CAR},
{"VAN", VisualObjectType::VAN},
{"BUS", VisualObjectType::BUS},
{"TRUCK", VisualObjectType::TRUCK},
{"TRICYCLE", VisualObjectType::TRICYCLE},
{"TRAFFICCONE", VisualObjectType::TRAFFICCONE},
{"UNKNOWN_MOVABLE", VisualObjectType::UNKNOWN_MOVABLE},
{"UNKNOWN_UNMOVABLE", VisualObjectType::UNKNOWN_UNMOVABLE},
{"MAX_OBJECT_TYPE", VisualObjectType::MAX_OBJECT_TYPE},
}

◆ kVisualType2NameMap

const std::map<VisualObjectType, std::string> apollo::perception::base::kVisualType2NameMap
Initial value:
= {
{VisualObjectType::CAR, "CAR"},
{VisualObjectType::VAN, "VAN"},
{VisualObjectType::BUS, "BUS"},
{VisualObjectType::TRUCK, "TRUCK"},
{VisualObjectType::TRICYCLE, "TRICYCLE"},
{VisualObjectType::TRAFFICCONE, "TRAFFICCONE"},
{VisualObjectType::UNKNOWN_MOVABLE, "UNKNOWN_MOVABLE"},
{VisualObjectType::UNKNOWN_UNMOVABLE, "UNKNOWN_UNMOVABLE"},
{VisualObjectType::MAX_OBJECT_TYPE, "MAX_OBJECT_TYPE"},
}

◆ kVisualTypeMap

const std::map<VisualObjectType, ObjectType> apollo::perception::base::kVisualTypeMap
Initial value:
= {
{VisualObjectType::CAR, ObjectType::VEHICLE},
{VisualObjectType::VAN, ObjectType::VEHICLE},
{VisualObjectType::BUS, ObjectType::VEHICLE},
{VisualObjectType::TRUCK, ObjectType::VEHICLE},
{VisualObjectType::TRICYCLE, ObjectType::BICYCLE},
{VisualObjectType::TRAFFICCONE, ObjectType::UNKNOWN_UNMOVABLE},
{VisualObjectType::UNKNOWN_UNMOVABLE, ObjectType::UNKNOWN_UNMOVABLE},
}

VisualObjectType mapping