24 :
VelodyneParser(config), previous_packet_stamp_(0), gps_base_usec_(0) {
30 const std::shared_ptr<VelodyneScan>& scan_msg,
31 std::shared_ptr<PointCloud> out_msg) {
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);
38 gps_base_usec_ = scan_msg->basetime();
40 for (
int i = 0; i < scan_msg->firing_pkts_size(); ++i) {
41 Unpack(scan_msg->firing_pkts(i), out_msg);
45 size_t size = out_msg->point_size();
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);
56 out_msg->set_width(out_msg->point_size());
59uint64_t Velodyne128Parser::GetTimestamp(
double base_time,
float time_offset,
62 double t = base_time + time_offset;
63 uint64_t timestamp =
GetGpsStamp(t, &previous_packet_stamp_, &gps_base_usec_);
72 std::shared_ptr<PointCloud> pc) {
73 float azimuth_diff, azimuth_corrected_f;
74 float last_azimuth_diff = 0.0f;
76 uint16_t azimuth_next = 0;
77 uint16_t azimuth_corrected = 0;
86 azimuth = azimuth_next;
91 static_cast<float>((36000 + azimuth_next - azimuth) % 36000);
92 last_azimuth_diff = azimuth_diff;
94 azimuth_diff = last_azimuth_diff;
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;
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];
111 float real_distance =
112 raw_distance.raw_distance * VSL128_DISTANCE_RESOLUTION;
113 float distance = real_distance + corrections.dist_correction;
115 uint64_t
timestamp =
static_cast<uint64_t
>(GetTimestamp(
116 basetime, (*
inner_time_)[block][j],
static_cast<uint16_t
>(block)));
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);
131 int intensity =
static_cast<int>(raw->
blocks[block].
data[k + 2]);
135 azimuth_corrected_f =
137 (azimuth_diff * (firing_order * CHANNEL_TDURATION) / SEQ_TDURATION);
139 (
static_cast<uint16_t
>(round(azimuth_corrected_f))) % 36000;
142 PointXYZIT* point_new = pc->add_point();
145 point_new->set_timestamp(timestamp);
146 ComputeCoords(real_distance, corrections, azimuth_corrected, point_new);
148 intensity = IntensityCompensate(corrections, raw_distance.raw_distance,
150 point_new->set_intensity(intensity);
156int Velodyne128Parser::IntensityCompensate(
const LaserCorrection& corrections,
157 const uint16_t raw_distance,
159 float focal_offset = 256 * (1 - corrections.focal_distance / 13100) *
160 (1 - corrections.focal_distance / 13100);
161 float focal_slope = corrections.focal_slope;
163 intensity +=
static_cast<int>(
165 static_cast<float>(std::abs(
167 256.0f * (1.0f -
static_cast<float>(raw_distance) / 65535.0f) *
168 (1.0f -
static_cast<float>(raw_distance) / 65535.0f))));
170 if (intensity < corrections.min_intensity) {
171 intensity = corrections.min_intensity;
174 if (intensity > corrections.max_intensity) {
175 intensity = corrections.max_intensity;
Cyber has builtin time type Time.
std::map< int, LaserCorrection > laser_corrections_
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)
Velodyne128Parser(const Config &config)
Velodyne data conversion class
const float(* inner_time_)[12][32]
bool is_scan_valid(int rotation, float distance)
uint64_t GetGpsStamp(double current_stamp, double *previous_stamp, uint64_t *gps_base_usec)
bool need_two_pt_correction_
void ComputeCoords(const float &raw_distance, const LaserCorrection &corrections, const uint16_t rotation, PointXYZIT *point)
Compute coords with the data in block
const float INNER_TIME_128[12][32]
constexpr int BLOCKS_PER_PACKET
uint16_t rotation
0-35999, divide by 100 to get degrees
uint8_t data[BLOCK_DATA_SIZE]
unsigned int gps_timestamp
RawBlock blocks[BLOCKS_PER_PACKET]
Velodyne HDL-64E 3D LIDAR data accessors