提交 df600e3e 编写于 作者: P pengronggui 提交者: Ronggui Peng

Drivers: add support velodyne-vlp32c

上级 c39b8965
frame_id: "velodyne32"
scan_channel: "/apollo/sensor/velodyne32/VelodyneScan"
rpm: 600.0
model: VLP32C
mode: STRONGEST
firing_data_port: 8308
use_sensor_sync: false
max_range: 200
min_range: 0.4
use_gps_time: true
calibration_online: false
calibration_file: "/apollo/modules/drivers/velodyne/params/VLP32C_calibration_example.yaml"
organized: false
convert_channel_name: "/apollo/sensor/velodyne32/PointCloud2"
use_poll_sync: true
is_main_frame: true
......@@ -254,6 +254,11 @@ VelodyneDriver* VelodyneDriverFactory::CreateDriver(const Config& config) {
driver->SetPacketRate(PACKET_RATE_HDL32E);
break;
}
case VLP32C: {
driver = new VelodyneDriver(config);
driver->SetPacketRate(PACKET_RATE_VLP32C);
break;
}
case VLP16: {
driver = new VelodyneDriver(config);
driver->SetPacketRate(PACKET_RATE_VLP16);
......
......@@ -36,6 +36,7 @@ constexpr double PACKET_RATE_HDL64E_S2 = 3472.17;
constexpr double PACKET_RATE_HDL64E_S3S = 3472.17;
constexpr double PACKET_RATE_HDL64E_S3D = 5789;
constexpr double PACKET_RATE_VLS128 = 6250.0;
constexpr double PACKET_RATE_VLP32C = 1507.0;
class VelodyneDriver {
public:
......
lasers:
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 0, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.4363323129985824,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 1, max_intensity: 255,
min_intensity: 0, rot_correction: 0.07330382858376185, vert_correction: -0.017453292519943295,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 2, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.029094638630745476,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 3, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.2729520417193932,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 4, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.19739673840055869,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 5, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 6, max_intensity: 255,
min_intensity: 0, rot_correction: -0.07330382858376185, vert_correction: -0.011641346110802179,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 7, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.15433946575385857,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 8, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.12660618393966866,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 9, max_intensity: 255,
min_intensity: 0, rot_correction: 0.07330382858376185, vert_correction: 0.005811946409141118,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 10, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.005811946409141118,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 11, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.10730284241261137,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 12, max_intensity: 255,
min_intensity: 0, rot_correction: -0.07330382858376185, vert_correction: -0.0930784090088576,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 13, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: 0.02326523892908441,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 14, max_intensity: 255,
min_intensity: 0, rot_correction: -0.07330382858376185, vert_correction: 0.011641346110802179,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 15, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.06981317007977318,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 16, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.08145451619057535,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 17, max_intensity: 255,
min_intensity: 0, rot_correction: 0.07330382858376185, vert_correction: 0.029094638630745476,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 18, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: 0.017453292519943295,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 19, max_intensity: 255,
min_intensity: 0, rot_correction: 0.07330382858376185, vert_correction: -0.06400122367063206,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 20, max_intensity: 255,
min_intensity: 0, rot_correction: -0.07330382858376185, vert_correction: -0.058171823968971005,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 21, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: 0.058171823968971005,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 22, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: 0.04071853144902771,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 23, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.04654793115068877,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 24, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: -0.05235987755982989,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 25, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: 0.12217304763960307,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 26, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: 0.08145451619057535,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 27, max_intensity: 255,
min_intensity: 0, rot_correction: 0.07330382858376185, vert_correction: -0.04071853144902771,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 28, max_intensity: 255,
min_intensity: 0, rot_correction: -0.07330382858376185, vert_correction: -0.03490658503988659,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 29, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: 0.2617993877991494,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 30, max_intensity: 255,
min_intensity: 0, rot_correction: -0.024434609527920613, vert_correction: 0.18034487160857407,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 31, max_intensity: 255,
min_intensity: 0, rot_correction: 0.024434609527920613, vert_correction: -0.02326523892908441,
vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 32, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 33, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 34, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 35, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 36, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 37, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 38, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 39, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 40, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 41, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 42, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 43, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 44, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 45, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 46, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 47, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 48, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 49, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 50, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 51, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 52, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 53, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 54, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 55, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 56, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 57, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 58, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 59, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 60, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 61, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 62, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
- {dist_correction: 0.0, dist_correction_x: 0.0, dist_correction_y: 0.0, focal_distance: 0.0,
focal_slope: 0.0, horiz_offset_correction: 0.0, laser_id: 63, max_intensity: 255,
min_intensity: 0, rot_correction: 0.0, vert_correction: 0.0, vert_offset_correction: 0.0}
num_lasers: 64
......@@ -303,6 +303,64 @@ const float INNER_TIME_128[12][32] = {
137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f,
140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f}};
const float INNER_TIME_VLP32C[12][32] = {
{0.000f, 0.000f, 2.304f, 2.304f, 4.608f, 4.608f, 6.912f, 6.912f,
9.216f, 9.216f, 11.520f, 11.520f, 13.824f, 13.824f, 16.128f, 16.128f,
18.432f, 18.432f, 20.736f, 20.736f, 23.040f, 23.040f, 25.344f, 25.344f,
27.648f, 27.648f, 29.952f, 29.952f, 32.256f, 32.256f, 34.560f, 34.560f},
{0.000f, 0.000f, 2.304f, 2.304f, 4.608f, 4.608f, 6.912f, 6.912f,
9.216f, 9.216f, 11.520f, 11.520f, 13.824f, 13.824f, 16.128f, 16.128f,
18.432f, 18.432f, 20.736f, 20.736f, 23.040f, 23.040f, 25.344f, 25.344f,
27.648f, 27.648f, 29.952f, 29.952f, 32.256f, 32.256f, 34.560f, 34.560f},
{55.296f, 55.296f, 57.600f, 57.600f, 59.904f, 59.904f, 62.208f, 62.208f,
64.512f, 64.512f, 66.816f, 66.816f, 69.120f, 69.120f, 71.424f, 71.424f,
73.728f, 73.728f, 76.032f, 76.032f, 78.336f, 78.336f, 80.640f, 80.640f,
82.944f, 82.944f, 85.248f, 85.248f, 87.552f, 87.552f, 89.856f, 89.856f},
{55.296f, 55.296f, 57.600f, 57.600f, 59.904f, 59.904f, 62.208f, 62.208f,
64.512f, 64.512f, 66.816f, 66.816f, 69.120f, 69.120f, 71.424f, 71.424f,
73.728f, 73.728f, 76.032f, 76.032f, 78.336f, 78.336f, 80.640f, 80.640f,
82.944f, 82.944f, 85.248f, 85.248f, 87.552f, 87.552f, 89.856f, 89.856f},
{110.592f, 110.592f, 112.896f, 112.896f, 115.200f, 115.200f, 117.504f,
117.504f, 119.808f, 119.808f, 122.112f, 122.112f, 124.416f, 124.416f,
126.720f, 126.720f, 129.024f, 129.024f, 131.328f, 131.328f, 133.632f,
133.632f, 135.936f, 135.936f, 138.240f, 138.240f, 140.544f, 140.544f,
142.848f, 142.848f, 145.152f, 145.152f},
{110.592f, 110.592f, 112.896f, 112.896f, 115.200f, 115.200f, 117.504f,
117.504f, 119.808f, 119.808f, 122.112f, 122.112f, 124.416f, 124.416f,
126.720f, 126.720f, 129.024f, 129.024f, 131.328f, 131.328f, 133.632f,
133.632f, 135.936f, 135.936f, 138.240f, 138.240f, 140.544f, 140.544f,
142.848f, 142.848f, 145.152f, 145.152f},
{165.888f, 165.888f, 168.192f, 168.192f, 170.496f, 170.496f, 172.800f,
172.800f, 175.104f, 175.104f, 177.408f, 177.408f, 179.712f, 179.712f,
182.016f, 182.016f, 184.320f, 184.320f, 186.624f, 186.624f, 188.928f,
188.928f, 191.232f, 191.232f, 193.536f, 193.536f, 195.840f, 195.840f,
198.144f, 198.144f, 200.448f, 200.448f},
{165.888f, 165.888f, 168.192f, 168.192f, 170.496f, 170.496f, 172.800f,
172.800f, 175.104f, 175.104f, 177.408f, 177.408f, 179.712f, 179.712f,
182.016f, 182.016f, 184.320f, 184.320f, 186.624f, 186.624f, 188.928f,
188.928f, 191.232f, 191.232f, 193.536f, 193.536f, 195.840f, 195.840f,
198.144f, 198.144f, 200.448f, 200.448f},
{221.184f, 221.184f, 223.488f, 223.488f, 225.792f, 225.792f, 228.096f,
228.096f, 230.400f, 230.400f, 232.704f, 232.704f, 235.008f, 235.008f,
237.312f, 237.312f, 239.616f, 239.616f, 241.920f, 241.920f, 244.224f,
244.224f, 246.528f, 246.528f, 248.832f, 248.832f, 251.136f, 251.136f,
253.440f, 253.440f, 255.744f, 255.744f},
{221.184f, 221.184f, 223.488f, 223.488f, 225.792f, 225.792f, 228.096f,
228.096f, 230.400f, 230.400f, 232.704f, 232.704f, 235.008f, 235.008f,
237.312f, 237.312f, 239.616f, 239.616f, 241.920f, 241.920f, 244.224f,
244.224f, 246.528f, 246.528f, 248.832f, 248.832f, 251.136f, 251.136f,
253.440f, 253.440f, 255.744f, 255.744f},
{276.480f, 276.480f, 278.784f, 278.784f, 281.088f, 281.088f, 283.392f,
283.392f, 285.696f, 285.696f, 288.000f, 288.000f, 290.304f, 290.304f,
292.608f, 292.608f, 294.912f, 294.912f, 297.216f, 297.216f, 299.520f,
299.520f, 301.824f, 301.824f, 304.128f, 304.128f, 306.432f, 306.432f,
308.736f, 308.736f, 311.040f, 311.040f},
{276.480f, 276.480f, 278.784f, 278.784f, 281.088f, 281.088f, 283.392f,
283.392f, 285.696f, 285.696f, 288.000f, 288.000f, 290.304f, 290.304f,
292.608f, 292.608f, 294.912f, 294.912f, 297.216f, 297.216f, 299.520f,
299.520f, 301.824f, 301.824f, 304.128f, 304.128f, 306.432f, 306.432f,
308.736f, 308.736f, 311.040f, 311.040f}};
} // namespace velodyne
} // namespace drivers
} // namespace apollo
......@@ -24,6 +24,9 @@ Velodyne32Parser::Velodyne32Parser(const Config& config)
: VelodyneParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
inner_time_ = &velodyne::INNER_TIME_HDL32E;
need_two_pt_correction_ = false;
if (config_.model() == VLP32C) {
inner_time_ = &velodyne::INNER_TIME_VLP32C;
}
}
void Velodyne32Parser::GeneratePointcloud(
......@@ -37,12 +40,18 @@ void Velodyne32Parser::GeneratePointcloud(
gps_base_usec_ = scan_msg->basetime();
size_t packets_size = scan_msg->firing_pkts_size();
for (size_t i = 0; i < packets_size; ++i) {
Unpack(scan_msg->firing_pkts(static_cast<int>(i)), out_msg);
last_time_stamp_ = out_msg->measurement_time();
ADEBUG << "stamp: " << std::fixed << last_time_stamp_;
if (config_.model() == VLP32C) {
for (size_t i = 0; i < packets_size; ++i) {
UnpackVLP32C(scan_msg->firing_pkts(static_cast<int>(i)), out_msg);
last_time_stamp_ = out_msg->measurement_time();
}
} else {
for (size_t i = 0; i < packets_size; ++i) {
Unpack(scan_msg->firing_pkts(static_cast<int>(i)), out_msg);
last_time_stamp_ = out_msg->measurement_time();
ADEBUG << "stamp: " << std::fixed << last_time_stamp_;
}
}
if (out_msg->point_size() == 0) {
// we discard this pointcloud if empty
AERROR << "All points is NAN!Please check velodyne:" << config_.model();
......@@ -54,10 +63,85 @@ void Velodyne32Parser::GeneratePointcloud(
uint64_t Velodyne32Parser::GetTimestamp(double base_time, float time_offset,
uint16_t block_id) {
double t = base_time - time_offset;
if (config_.model() == VLP32C) {
t = base_time + time_offset;
}
uint64_t timestamp = GetGpsStamp(t, &previous_packet_stamp_, &gps_base_usec_);
return timestamp;
}
void Velodyne32Parser::UnpackVLP32C(const VelodynePacket& pkt,
std::shared_ptr<PointCloud> pc) {
const RawPacket* raw = (const RawPacket*)pkt.data().c_str();
double basetime = raw->gps_timestamp; // usec
float azimuth = 0.0f;
float azimuth_diff = 0.0f;
float last_azimuth_diff = 0.0f;
float azimuth_corrected_f = 0.0f;
int azimuth_corrected = 0;
for (int i = 0; i < BLOCKS_PER_PACKET; i++) { // 12
azimuth = static_cast<float>(raw->blocks[i].rotation);
if (i < (BLOCKS_PER_PACKET - 1)) {
azimuth_diff = static_cast<float>(
(36000 + raw->blocks[i + 1].rotation - raw->blocks[i].rotation) %
36000);
last_azimuth_diff = azimuth_diff;
} else {
azimuth_diff = last_azimuth_diff;
}
for (int laser_id = 0, k = 0; laser_id < SCANS_PER_BLOCK;
++laser_id, k += RAW_SCAN_SIZE) { // 32, 3
LaserCorrection& corrections = calibration_.laser_corrections_[laser_id];
union RawDistance raw_distance;
raw_distance.bytes[0] = raw->blocks[i].data[k];
raw_distance.bytes[1] = raw->blocks[i].data[k + 1];
// compute time
uint64_t timestamp = static_cast<uint64_t>(GetTimestamp(
basetime, (*inner_time_)[i][laser_id], static_cast<uint16_t>(i)));
if (laser_id == SCANS_PER_BLOCK - 1) {
// set header stamp before organize the point cloud
pc->set_measurement_time(static_cast<double>(timestamp) / 1e9);
}
azimuth_corrected_f =
azimuth + (azimuth_diff * (static_cast<float>(laser_id) / 2.0f) *
CHANNEL_TDURATION / SEQ_TDURATION);
azimuth_corrected =
static_cast<int>(round(fmod(azimuth_corrected_f, 36000.0)));
float real_distance =
raw_distance.raw_distance * VLP32_DISTANCE_RESOLUTION;
float distance = real_distance + corrections.dist_correction;
// AINFO << "raw_distance:" << raw_distance.raw_distance << ", distance:"
// << distance;
if (raw_distance.raw_distance == 0 ||
!is_scan_valid(azimuth_corrected, distance)) {
if (config_.organized()) {
apollo::drivers::PointXYZIT* point_new = pc->add_point();
point_new->set_x(nan);
point_new->set_y(nan);
point_new->set_z(nan);
point_new->set_timestamp(timestamp);
point_new->set_intensity(0);
}
continue;
}
apollo::drivers::PointXYZIT* point = pc->add_point();
point->set_timestamp(timestamp);
// Position Calculation, append this point to the cloud
ComputeCoords(real_distance, corrections,
static_cast<uint16_t>(azimuth_corrected), point);
point->set_intensity(raw->blocks[i].data[k + 2]);
}
}
}
void Velodyne32Parser::Unpack(const VelodynePacket& pkt,
std::shared_ptr<PointCloud> pc) {
// const RawPacket* raw = (const RawPacket*)&pkt.data[0];
......@@ -112,6 +196,9 @@ void Velodyne32Parser::Unpack(const VelodynePacket& pkt,
}
void Velodyne32Parser::Order(std::shared_ptr<PointCloud> cloud) {
if (config_.model() == VLP32C) {
return;
}
int width = 32;
cloud->set_width(width);
int height = cloud->point_size() / cloud->width();
......
......@@ -205,7 +205,7 @@ VelodyneParser *VelodyneParserFactory::CreateParser(Config source_config) {
if (config.model() == VLP16) {
config.set_calibration_online(false);
return new Velodyne16Parser(config);
} else if (config.model() == HDL32E) {
} else if (config.model() == HDL32E || config.model() == VLP32C) {
config.set_calibration_online(false);
return new Velodyne32Parser(config);
} else if (config.model() == HDL64E_S3S || config.model() == HDL64E_S3D ||
......
......@@ -327,6 +327,7 @@ class Velodyne32Parser : public VelodyneParser {
uint64_t GetTimestamp(double base_time, float time_offset,
uint16_t laser_block_id);
void Unpack(const VelodynePacket& pkt, std::shared_ptr<PointCloud> pc);
void UnpackVLP32C(const VelodynePacket& pkt, std::shared_ptr<PointCloud> pc);
// Previous Velodyne packet time stamp. (offset to the top hour)
double previous_packet_stamp_;
uint64_t gps_base_usec_; // full time
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册