Apollo 10.0
自动驾驶开放平台
velodyne128_parser.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2017 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
16
18
19namespace apollo {
20namespace drivers {
21namespace velodyne {
22
24 : VelodyneParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
27}
28
30 const std::shared_ptr<VelodyneScan>& scan_msg,
31 std::shared_ptr<PointCloud> out_msg) {
32 // allocate a point cloud with same time and frame ID as raw data
33 out_msg->mutable_header()->set_frame_id(scan_msg->header().frame_id());
34 out_msg->mutable_header()->set_timestamp_sec(cyber::Time().Now().ToSecond());
35 out_msg->set_height(1);
36
37 // us
38 gps_base_usec_ = scan_msg->basetime();
39
40 for (int i = 0; i < scan_msg->firing_pkts_size(); ++i) {
41 Unpack(scan_msg->firing_pkts(i), out_msg);
42 last_time_stamp_ = out_msg->measurement_time();
43 }
44
45 size_t size = out_msg->point_size();
46 if (size == 0) {
47 // we discard this pointcloud if empty
48 AERROR << "All points is NAN!Please check velodyne:" << config_.model();
49 return;
50 } else {
51 const auto timestamp =
52 out_msg->point(static_cast<int>(size) - 1).timestamp();
53 out_msg->set_measurement_time(static_cast<double>(timestamp) / 1e9);
54 out_msg->mutable_header()->set_lidar_timestamp(timestamp);
55 }
56 out_msg->set_width(out_msg->point_size());
57}
58
59uint64_t Velodyne128Parser::GetTimestamp(double base_time, float time_offset,
60 uint16_t block_id) {
61 (void)block_id;
62 double t = base_time + time_offset;
63 uint64_t timestamp = GetGpsStamp(t, &previous_packet_stamp_, &gps_base_usec_);
64 return timestamp;
65}
66
67void Velodyne128Parser::Order(std::shared_ptr<PointCloud> cloud) {
68 (void)cloud;
69}
70
71void Velodyne128Parser::Unpack(const VelodynePacket& pkt,
72 std::shared_ptr<PointCloud> pc) {
73 float azimuth_diff, azimuth_corrected_f;
74 float last_azimuth_diff = 0.0f;
75 uint16_t azimuth = 0;
76 uint16_t azimuth_next = 0;
77 uint16_t azimuth_corrected = 0;
78 const RawPacket* raw = (const RawPacket*)pkt.data().c_str();
79 double basetime = raw->gps_timestamp;
80
81 for (int block = 0; block < BLOCKS_PER_PACKET; block++) {
82 // Calculate difference between current and next block's azimuth angle.
83 if (block == 0) {
84 azimuth = raw->blocks[block].rotation;
85 } else {
86 azimuth = azimuth_next;
87 }
88 if (block < (BLOCKS_PER_PACKET - 1)) {
89 azimuth_next = raw->blocks[block + 1].rotation;
90 azimuth_diff =
91 static_cast<float>((36000 + azimuth_next - azimuth) % 36000);
92 last_azimuth_diff = azimuth_diff;
93 } else {
94 azimuth_diff = last_azimuth_diff;
95 }
96
97 /*condition added to avoid calculating points which are not
98 in the interesting defined area (min_angle < area < max_angle)*/
99 for (int j = 0, k = 0; j < SCANS_PER_BLOCK; j++, k += RAW_SCAN_SIZE) {
100 uint8_t group = static_cast<uint8_t>(block % 4);
101 uint8_t chan_id = static_cast<uint8_t>(j + group * 32);
102 uint8_t firing_order = chan_id / 8;
103 firing_order = 0;
104 LaserCorrection& corrections = calibration_.laser_corrections_[chan_id];
105 // distance extraction
106 // union two_bytes tmp;
107 union RawDistance raw_distance;
108 raw_distance.bytes[0] = raw->blocks[block].data[k];
109 raw_distance.bytes[1] = raw->blocks[block].data[k + 1];
110
111 float real_distance =
112 raw_distance.raw_distance * VSL128_DISTANCE_RESOLUTION;
113 float distance = real_distance + corrections.dist_correction;
114
115 uint64_t timestamp = static_cast<uint64_t>(GetTimestamp(
116 basetime, (*inner_time_)[block][j], static_cast<uint16_t>(block)));
117 if (!is_scan_valid(azimuth, distance)) {
118 // todo organized
119 if (config_.organized()) {
120 apollo::drivers::PointXYZIT* point_new = pc->add_point();
121 point_new->set_x(nan);
122 point_new->set_y(nan);
123 point_new->set_z(nan);
124 point_new->set_timestamp(timestamp);
125 point_new->set_intensity(0);
126 }
127 continue;
128 }
129
130 // if (pointInRange(distance)) {
131 int intensity = static_cast<int>(raw->blocks[block].data[k + 2]);
132
135 azimuth_corrected_f =
136 azimuth +
137 (azimuth_diff * (firing_order * CHANNEL_TDURATION) / SEQ_TDURATION);
138 azimuth_corrected =
139 (static_cast<uint16_t>(round(azimuth_corrected_f))) % 36000;
140
141 // add new point
142 PointXYZIT* point_new = pc->add_point();
143
144 // compute time , time offset is zero
145 point_new->set_timestamp(timestamp);
146 ComputeCoords(real_distance, corrections, azimuth_corrected, point_new);
147
148 intensity = IntensityCompensate(corrections, raw_distance.raw_distance,
149 intensity);
150 point_new->set_intensity(intensity);
151 }
152 // }
153 }
154}
155
156int Velodyne128Parser::IntensityCompensate(const LaserCorrection& corrections,
157 const uint16_t raw_distance,
158 int intensity) {
159 float focal_offset = 256 * (1 - corrections.focal_distance / 13100) *
160 (1 - corrections.focal_distance / 13100);
161 float focal_slope = corrections.focal_slope;
162
163 intensity += static_cast<int>(
164 focal_slope *
165 static_cast<float>(std::abs(
166 focal_offset -
167 256.0f * (1.0f - static_cast<float>(raw_distance) / 65535.0f) *
168 (1.0f - static_cast<float>(raw_distance) / 65535.0f))));
169
170 if (intensity < corrections.min_intensity) {
171 intensity = corrections.min_intensity;
172 }
173
174 if (intensity > corrections.max_intensity) {
175 intensity = corrections.max_intensity;
176 }
177 return intensity;
178}
179
180} // namespace velodyne
181} // namespace drivers
182} // namespace apollo
Cyber has builtin time type Time.
Definition time.h:31
std::map< int, LaserCorrection > laser_corrections_
Definition calibration.h:70
void GeneratePointcloud(const std::shared_ptr< VelodyneScan > &scan_msg, std::shared_ptr< PointCloud > out_msg)
Set up for data processing.
void Order(std::shared_ptr< PointCloud > cloud)
bool is_scan_valid(int rotation, float distance)
uint64_t GetGpsStamp(double current_stamp, double *previous_stamp, uint64_t *gps_base_usec)
void ComputeCoords(const float &raw_distance, const LaserCorrection &corrections, const uint16_t rotation, PointXYZIT *point)
Compute coords with the data in block
#define AERROR
Definition log.h:44
const float INNER_TIME_128[12][32]
constexpr int BLOCKS_PER_PACKET
Definition driver.h:33
class register implement
Definition arena_queue.h:37
uint16_t rotation
0-35999, divide by 100 to get degrees
RawBlock blocks[BLOCKS_PER_PACKET]
Velodyne HDL-64E 3D LIDAR data accessors