Object
用于表征一帧检测中每个检测物体/检测框的一些属性,存放位置:apollo\modules\perception\base
中。
Object
结构体
表征单个目标,包括:
- 该目标的
ID
,convex hull
,三维尺寸
、朝向
、位置信息
及variance
; - 目标
类别
及概率
,类别参考Object Type
中的定义; - 目标
存在的可能性
; - Tracking相关的属性:
Track ID
,注:目标ID是Per Frame的,没做帧间配准;速度
,加速度大小
及不确定性
;tracking time
及latest track time
;Motion State
{UNKNOWN
,MOVING
,STATIONARY
},定义于Object Type
中;Tailgating
: Trajectory of objects;
CIPV
属性;车灯
属性;supplement
:包括lidar,radar,camera和fusion;
struct alignas(16) Object {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Object();
std::string ToString() const;
void Reset();
// @brief object id per frame, required
int id = -1;
// @brief convex hull of the object, required
PointCloud<PointD> polygon;
// oriented boundingbox information
// @brief main direction of the object, required
Eigen::Vector3f direction = Eigen::Vector3f(1, 0, 0);
/*@brief the yaw angle, theta = 0.0 <=> direction(1, 0, 0),
currently roll and pitch are not considered,
make sure direction and theta are consistent, required
*/
float theta = 0.0f;
// @brief theta variance, required
float theta_variance = 0.0f;
// @brief center of the boundingbox (cx, cy, cz), required
Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0);
// @brief covariance matrix of the center uncertainty, required
Eigen::Matrix3f center_uncertainty;
/* @brief size = [length, width, height] of boundingbox
length is the size of the main direction, required
*/
Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0);
// @brief size variance, required
Eigen::Vector3f size_variance = Eigen::Vector3f(0, 0, 0);
// @brief anchor point, required
Eigen::Vector3d anchor_point = Eigen::Vector3d(0, 0, 0);
// @brief object type, required
ObjectType type = ObjectType::UNKNOWN;
// @brief probability for each type, required
std::vector<float> type_probs;
// @brief object sub-type, optional
ObjectSubType sub_type = ObjectSubType::UNKNOWN;
// @brief probability for each sub-type, optional
std::vector<float> sub_type_probs;
// @brief existence confidence, required
float confidence = 1.0f;
// tracking information
// @brief track id, required
int track_id = -1;
// @brief velocity of the object, required
Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
// @brief covariance matrix of the velocity uncertainty, required
Eigen::Matrix3f velocity_uncertainty;
// @brief if the velocity estimation is converged, true by default
bool velocity_converged = true;
// @brief velocity confidence, required
float velocity_confidence = 1.0f;
// @brief acceleration of the object, required
Eigen::Vector3f acceleration = Eigen::Vector3f(0, 0, 0);
// @brief covariance matrix of the acceleration uncertainty, required
Eigen::Matrix3f acceleration_uncertainty;
// @brief age of the tracked object, required
double tracking_time = 0.0;
// @brief timestamp of latest measurement, required
double latest_tracked_time = 0.0;
// @brief motion state of the tracked object, required
MotionState motion_state = MotionState::UNKNOWN;
// // Tailgating (trajectory of objects)
std::array<Eigen::Vector3d, 100> drops;
std::size_t drop_num = 0;
// // CIPV
bool b_cipv = false;
// @brief brake light, left-turn light and right-turn light score, optional
CarLight car_light;
// @brief sensor-specific object supplements, optional
LidarObjectSupplement lidar_supplement;
RadarObjectSupplement radar_supplement;
CameraObjectSupplement camera_supplement;
FusionObjectSupplement fusion_supplement;
// @debug feature to be used for semantic mapping
// std::shared_ptr<apollo::prediction::Feature> feature;
};
using ObjectPtr = std::shared_ptr<Object>;
using ObjectConstPtr = std::shared_ptr<const Object>;
Object Type
结构体
主要包括:
- 所有模块共用的
ObjectType
; - 模块内部使用的
ObjectType
:- Lidar:
InternalObjectType
; - Camera:
VisualObjectType
;
- Lidar:
- 细粒度定义的ObjectType:
ObjectSubType
; - 运动状态的定义:
MotionState
; - 视觉检测的Landmark定义:
VisualLandmarkType
; - Type、String之间的各种映射;
// @brief general object type
enum class ObjectType {
UNKNOWN = 0,
UNKNOWN_MOVABLE = 1,
UNKNOWN_UNMOVABLE = 2,
PEDESTRIAN = 3,
BICYCLE = 4,
VEHICLE = 5,
MAX_OBJECT_TYPE = 6,
};
// @brief internal object type used by lidar perception
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,
};
// @brief internal object type used by visual perception
enum class VisualObjectType {
CAR,
VAN,
BUS,
TRUCK,
BICYCLE,
TRICYCLE,
PEDESTRIAN,
TRAFFICCONE,
UNKNOWN_MOVABLE,
UNKNOWN_UNMOVABLE,
MAX_OBJECT_TYPE,
};
// @brief fine-grained object types
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,
MAX_OBJECT_TYPE = 12,
};
// @brief motion state
enum class MotionState {
UNKNOWN = 0,
MOVING = 1,
STATIONARY = 2,
};
/**
* Landmark types and mapping
*/
enum class VisualLandmarkType {
RoadArrow,
RoadText,
TrafficSign,
TrafficLight,
MAX_LANDMARK_TYPE,
};
Object Supplement
结构体
提供该Object
的一些原始数据,以及不在Object
类别定义中的各种传感器特有的东西,Object
定义为所有module共用的部分:
LidarObjectSupplement
: 包括点云数据及一些其他属性:
struct alignas(16) LidarObjectSupplement {
void Reset() {
......
}
// @brief orientation estimateed indicator
bool is_orientation_ready = false;
// @brief valid only for on_use = true
bool on_use = false;
// @brief cloud of the object in lidar coordinates
base::AttributePointCloud<PointF> cloud;
// @brief cloud of the object in world coordinates
base::AttributePointCloud<PointD> cloud_world;
// @brief background indicator
bool is_background = false;
// @brief false positive indicator
bool is_fp = false;
// @brief false positive probability
float fp_prob = 0.f;
// @brief whether this object is in roi
bool is_in_roi = false;
// @brief number of cloud points in roi
size_t num_points_in_roi = 0;
// @brief object height above ground
float height_above_ground = std::numeric_limits<float>::max();
// @brief raw probability of each classification method
std::vector<std::vector<float>> raw_probs;
std::vector<std::string> raw_classification_methods;
};
RadarObjectSupplement
:包括原始的速度观测量:
struct alignas(16) RadarObjectSupplement {
void Reset() {
.....
}
// @brief valid only for on_use = true
bool on_use = false;
/* @brief (range, angle) in radar polar coordinate system
x for forward and y for left
*/
float range = 0.0f;
float angle = 0.0f;
float relative_radial_velocity = 0.0f;
float relative_tangential_velocity = 0.0f;
float radial_velocity = 0.0f;
};
CameraObjectSupplement
:包括2D bbox、area 、ID等:
struct alignas(16) CameraObjectSupplement {
CameraObjectSupplement() { Reset(); }
void Reset() {
.....
}
// @brief valid only for on_use = true
bool on_use = false;
// @brief camera sensor name
std::string sensor_name;
// @brief 2d box
BBox2D<float> box;
// @brief projected 2d box
BBox2D<float> projected_box;
// @brief local track id
int local_track_id = -1;
// @brief 2Dto3D, pts8.resize(16), x, y...
std::vector<float> pts8;
// @brief front box
BBox2D<float> front_box;
// @brief back box
BBox2D<float> back_box;
std::vector<float> object_feature;
// @brief alpha angle from KITTI: Observation angle of object, in [-pi..pi]
double alpha = 0.0;
double truncated_horizontal = 0.0;
double truncated_vertical = 0.0;
// @brief center in camera coordinate system
Eigen::Vector3f local_center = Eigen::Vector3f(0.0f, 0.0f, 0.0f);
// @brief visual object type, only used in camera module
VisualObjectType visual_type = VisualObjectType::MAX_OBJECT_TYPE;
std::vector<float> visual_type_probs;
//----------------------------------------------------------------
// area ID, corner ID and face ID
//----------------------------------------------------------------
// 8 | 1 | 2 a
// --------- 0-----1 ^
// | | | | |
// 7 | 0 | 3 d| |b
// | | | |
// --------- 3-----2
// 6 | 5 | 4 c
//----------------------------------------------------------------
int area_id;
// @brief visible ratios
float visible_ratios[4];
// @brief cut off ratios on width, length (3D)
// cut off ratios on left, right (2D)
float cut_off_ratios[4];
};
FusionObjectSupplement
:提供Fusion
中的SensorObjectMeasurement
,主要也包括2D bbox:
struct SensorObjectMeasurement {
void Reset() {
.....
}
std::string sensor_id = "unknown_sensor";
double timestamp = 0.0;
int track_id = -1;
Eigen::Vector3d center = Eigen::Vector3d(0, 0, 0);
float theta = 0.0f;
Eigen::Vector3f size = Eigen::Vector3f(0, 0, 0);
Eigen::Vector3f velocity = Eigen::Vector3f(0, 0, 0);
ObjectType type = ObjectType::UNKNOWN;
// @brief only for camera measurement
BBox2D<float> box;
};
struct alignas(16) FusionObjectSupplement {
FusionObjectSupplement() { measurements.reserve(5); }
void Reset() {
on_use = false;
measurements.clear();
}
bool on_use = false;
std::vector<SensorObjectMeasurement> measurements;
};
Frame
用于表征每一帧的信息,包括多个Object
及各个sensor的supplement
,存放位置:apollo\modules\perception\base
中。
Frame
结构体
包括Sensor Info
、Timestamp
,该帧中所有的Objects
,sensor在世界坐标系下的pose
以及各个sensor的supplement
:
struct alignas(16) Frame {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Frame() { sensor2world_pose.setIdentity(); }
void Reset() {
....
}
// @brief sensor information
SensorInfo sensor_info;
double timestamp = 0.0;
std::vector<std::shared_ptr<Object>> objects;
Eigen::Affine3d sensor2world_pose;
// sensor-specific frame supplements
LidarFrameSupplement lidar_frame_supplement;
RadarFrameSupplement radar_frame_supplement;
CameraFrameSupplement camera_frame_supplement;
UltrasonicFrameSupplement ultrasonic_frame_supplement;
};
SensorInfo
结构体
文件位于apollo\modules\perception\base\sensor_meta.h
中。
主要包括:
SensorType
:Lidar,Radar,Camera,Ultrasonic;SensorOrientation
:安装位置:左前、右前等;Sensor Name
和Frame ID
;
/**
* @brief 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 SensorType {
UNKNOWN_SENSOR_TYPE = -1,
VELODYNE_64 = 0,
VELODYNE_32 = 1,
VELODYNE_16 = 2,
LDLIDAR_4 = 3,
LDLIDAR_1 = 4,
SHORT_RANGE_RADAR = 5,
LONG_RANGE_RADAR = 6,
MONOCULAR_CAMERA = 7,
STEREO_CAMERA = 8,
ULTRASONIC = 9,
VELODYNE_128 = 10,
SENSOR_TYPE_NUM
};
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
};
struct SensorInfo {
std::string name = "UNKNONW_SENSOR";
SensorType type = SensorType::UNKNOWN_SENSOR_TYPE;
SensorOrientation orientation = SensorOrientation::FRONT;
std::string frame_id = "UNKNOWN_FRAME_ID";
void Reset() {
.....
}
};
Frame Supplement
结构体
提供Frame
中的其他Supplement
信息:
LidarFrameSupplement
:提供该帧原始点云;
struct alignas(16) LidarFrameSupplement {
// @brief valid only when on_use = true
bool on_use = false;
// @brief only reference of the original cloud in lidar coordinate system
std::shared_ptr<AttributePointCloud<PointF>> cloud_ptr;
void Reset() {
on_use = false;
cloud_ptr = nullptr;
}
};
RadarFrameSupplement
:没提供东西;
struct alignas(16) CameraFrameSupplement {
// @brief valid only when on_use = true
bool on_use = false;
// @brief only reference of the image data
Image8UPtr image_ptr = nullptr;
// TODO(guiyilin): modify interfaces of visualizer, use Image8U
std::shared_ptr<Blob<uint8_t>> image_blob = nullptr;
void Reset() {
....
}
};
UltrasonicFrameSupplement
:提供该帧即将碰撞边界信息;
struct alignas(16) UltrasonicFrameSupplement {
// @brief valid only when on_use = true
bool on_use = false;
// @brief only reference of the image data
std::shared_ptr<ImpendingCollisionEdges> impending_collision_edges_ptr;
void Reset() {
....
}
};