apollo/modules/perception/proto/perception_obstacle.proto文件定义了障碍物格式
根据apollo的代码,感知层要发出去的数据包括:
message PerceptionObstacles {
repeated PerceptionObstacle perception_obstacle = 1; // An array of obstacles 障碍物
optional common.Header header = 2; // Header 协议头?
optional common.ErrorCode error_code = 3 [default = OK]; //错误代码
optional LaneMarkers lane_marker = 4;//车道线
optional CIPVInfo cipv_info = 5; // Closest In Path Vehicle (CIPV) 最近的车辆
}
其中 PerceptionObstacle的定义为:
message PerceptionObstacle {
optional int32 id = 1; // obstacle ID.
// obstacle position in the world coordinate system.
optional common.Point3D position = 2; //障碍物的3D位置
optional double theta = 3; // heading in the world coordinate system. //航向 方位
optional common.Point3D velocity = 4; // obstacle velocity.//速度
// Size of obstacle bounding box. 障碍物盒子
optional double length = 5; // obstacle length.//长
optional double width = 6; // obstacle width.//宽
optional double height = 7; // obstacle height.//高
repeated common.Point3D polygon_point = 8; // obstacle corner points. 障碍角点
// duration of an obstacle since detection in s.//观测到的障碍物的持续时间
optional double tracking_time = 9;
enum Type {//类型 是否移动、人、自行车、乘用车
UNKNOWN = 0;
UNKNOWN_MOVABLE = 1;
UNKNOWN_UNMOVABLE = 2;
PEDESTRIAN = 3; // Pedestrian, usually determined by moving behavior.
BICYCLE = 4; // bike, motor bike
VEHICLE = 5; // Passenger car or truck.
};
optional Type type = 10; // obstacle type
optional double timestamp = 11; // GPS time in seconds.
// Just for offline debugging, will not fill this field onboard.
// Format: [x0, y0, z0, x1, y1, z1...]
repeated double point_cloud = 12 [packed = true];
optional double confidence = 13 [deprecated = true];
enum ConfidenceType {//信任类型?激光雷达与摄像头,或者与毫米波雷达融合?
CONFIDENCE_UNKNOWN = 0;
CONFIDENCE_CNN = 1;
CONFIDENCE_RADAR = 2;
};
optional ConfidenceType confidence_type = 14 [deprecated = true];
// trajectory of object.
repeated common.Point3D drops = 15 [deprecated = true];
// The following fields are new added in Apollo 4.0
optional common.Point3D acceleration = 16; // obstacle acceleration
// a stable obstacle point in the world coordinate system
// position defined above is the obstacle bounding box ground center
optional common.Point3D anchor_point = 17;
optional BBox2D bbox2d = 18;//2D坐标点 四个点的坐标 见message BBox2D
enum SubType {
ST_UNKNOWN = 0;
ST_UNKNOWN_MOVABLE = 1;
ST_UNKNOWN_UNMOVABLE = 2;
ST_CAR = 3;
ST_VAN = 4;
ST_TRUCK = 5;
ST_BUS = 6;
ST_CYCLIST = 7;
ST_MOTORCYCLIST = 8;
ST_TRICYCLIST = 9;
ST_PEDESTRIAN = 10;
ST_TRAFFICCONE = 11;
};
optional SubType sub_type = 19; // obstacle sub_type 障碍子类型
repeated SensorMeasurement measurements = 20; // sensor measurements ???
// orthogonal distance between obstacle lowest point and ground plane
optional double height_above_ground = 21 [default = nan];//障碍物最低点与地平面之间的正交距离
// position covariance which is a row-majored 3x3 matrix
repeated double position_covariance = 22 [packed = true];//位置协方差
// velocity covariance which is a row-majored 3x3 matrix
repeated double velocity_covariance = 23 [packed = true];//速度协方差
// acceleration covariance which is a row-majored 3x3 matrix
repeated double acceleration_covariance = 24 [packed = true];//加速度协方差
// lights of vehicles
optional LightStatus light_status = 25;//灯光状态 左右转向、大灯等 见message LightStatus说明
}
错误码,主要关注预测的错误码:
syntax = "proto2";
package apollo.common;
// Error codes enum for API's categorized by modules.
enum ErrorCode {
// No error, returns on success.
OK = 0;
// Control module error codes start from here.
CONTROL_ERROR = 1000;
CONTROL_INIT_ERROR = 1001;
CONTROL_COMPUTE_ERROR = 1002;
// Canbus module error codes start from here.
CANBUS_ERROR = 2000;
CAN_CLIENT_ERROR_BASE = 2100;
CAN_CLIENT_ERROR_OPEN_DEVICE_FAILED = 2101;
CAN_CLIENT_ERROR_FRAME_NUM = 2102;
CAN_CLIENT_ERROR_SEND_FAILED = 2103;
CAN_CLIENT_ERROR_RECV_FAILED = 2104;
// Localization module error codes start from here.
LOCALIZATION_ERROR = 3000;
LOCALIZATION_ERROR_MSG = 3100;
LOCALIZATION_ERROR_LIDAR = 3200;
LOCALIZATION_ERROR_INTEG = 3300;
LOCALIZATION_ERROR_GNSS = 3400;
// Perception module error codes start from here.//感知层错误码
PERCEPTION_ERROR = 4000;//
PERCEPTION_ERROR_TF = 4001;//坐标转换错误码
PERCEPTION_ERROR_PROCESS = 4002;//传感器预测过程
PERCEPTION_FATAL = 4003;
PERCEPTION_ERROR_NONE = 4004;
PERCEPTION_ERROR_UNKNOWN = 4005;
// Prediction module error codes start from here.
PREDICTION_ERROR = 5000;
// Planning module error codes start from here
PLANNING_ERROR = 6000;
PLANNING_ERROR_NOT_READY = 6001;
// HDMap module error codes start from here
HDMAP_DATA_ERROR = 7000;
// Routing module error codes
ROUTING_ERROR = 8000;
ROUTING_ERROR_REQUEST = 8001;
ROUTING_ERROR_RESPONSE = 8002;
ROUTING_ERROR_NOT_READY = 8003;
// Indicates an input has been exhausted.
END_OF_INPUT = 9000;
// HTTP request error codes.
HTTP_LOGIC_ERROR = 10000;
HTTP_RUNTIME_ERROR = 10001;
// Relative Map error codes.
RELATIVE_MAP_ERROR = 11000; // general relative map error code
RELATIVE_MAP_NOT_READY = 11001;
// Driver error codes.
DRIVER_ERROR_GNSS = 12000;
DRIVER_ERROR_VELODYNE = 13000;
}
message StatusPb {
optional ErrorCode error_code = 1 [default = OK];
optional string msg = 2;
}
header:
message Header {
// Message publishing time in seconds. It is recommended to obtain
// timestamp_sec from ros::Time::now(), right before calling
// SerializeToString() and publish().
optional double timestamp_sec = 1;
// Module name.
optional string module_name = 2;
// Sequence number for each message. Each module maintains its own counter for
// sequence_num, always starting from 1 on boot.
optional uint32 sequence_num = 3;
// Lidar Sensor timestamp for nano-second.
optional uint64 lidar_timestamp = 4;
// Camera Sensor timestamp for nano-second.
optional uint64 camera_timestamp = 5;
// Radar Sensor timestamp for nano-second.
optional uint64 radar_timestamp = 6;
// data version
optional uint32 version = 7 [default = 1];
optional StatusPb status = 8;
optional string frame_id = 9;
}
路标线、临近车辆
message LaneMarker {
optional apollo.hdmap.LaneBoundaryType.Type lane_type = 1;
optional double quality = 2; // range = [0,1]; 1 = the best quality
optional int32 model_degree = 3;
// equation X = c3 * Z^3 + c2 * Z^2 + c1 * Z + c0
optional double c0_position = 4;
optional double c1_heading_angle = 5;
optional double c2_curvature = 6;
optional double c3_curvature_derivative = 7;
optional double view_range = 8;
optional double longitude_start = 9;
optional double longitude_end = 10;
}
message LaneMarkers {
optional LaneMarker left_lane_marker = 1;
optional LaneMarker right_lane_marker = 2;
repeated LaneMarker next_left_lane_marker = 3;
repeated LaneMarker next_right_lane_marker = 4;
}
message CIPVInfo {
optional int32 cipv_id = 1;
repeated int32 potential_cipv_id = 2;
}