syntax = "proto2"; package apollo.drivers.velodyne; import "modules/common/proto/header.proto"; enum Model { UNKNOWN = 0; HDL64E_S3S = 1; HDL64E_S3D = 2; HDL64E_S2 = 3; HDL32E = 4; VLP16 = 5; VLP32C = 6; VLS128 = 7; } enum Mode { STRONGEST = 1; LAST = 2; DUAL = 3; } message VelodynePacket { optional uint64 stamp = 1; optional bytes data = 2; } message VelodyneScan { optional apollo.common.Header header = 1; optional Model model = 2; // velodyne device model optional Mode mode = 3; // velodyne work mode repeated VelodynePacket firing_pkts = 4; // for HDL32 and VLP16 repeated VelodynePacket positioning_pkts = 5; // velodyne device serial number, corresponds to a specific calibration file optional string sn = 6; optional uint64 basetime = 7 [default = 0]; }