Apollo 10.0
自动驾驶开放平台
apollo::drivers::velodyne 命名空间参考

class  Calibration
 Calibration class storing entire configuration for the Velodyne 更多...
 
class  Compensator
 
class  CompensatorComponent
 
struct  CompensatorConfig
 
struct  Config
 
class  Convert
 
struct  FusionConfig
 
class  Input
 Pure virtual Velodyne input base class 更多...
 
struct  LaserCorrection
 correction values for a single laser 更多...
 
struct  NMEATime
 
class  OnlineCalibration
 
class  PriSecFusionComponent
 
struct  RawBlock
 Raw Velodyne data block. 更多...
 
union  RawDistance
 used for unpacking the first two data bytes in a block 更多...
 
struct  RawPacket
 Raw Velodyne packet. 更多...
 
class  SocketInput
 Live Velodyne input from socket. 更多...
 
class  Velodyne128Parser
 
class  Velodyne16Parser
 
class  Velodyne32Parser
 
class  Velodyne64Driver
 
class  Velodyne64Parser
 
class  VelodyneConvertComponent
 
class  VelodyneDriver
 
class  VelodyneDriverComponent
 
class  VelodyneDriverFactory
 
struct  VelodynePacket
 
class  VelodyneParser
 Velodyne data conversion class 更多...
 
class  VelodyneParserFactory
 
struct  VelodyneScan
 

类型定义

typedef std::shared_ptr< NMEATimeNMEATimePtr
 

枚举

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 }
 
enum  StatusType {
  HOURS = 72 , MINUTES = 77 , SECONDS = 83 , DATE = 68 ,
  MONTH = 78 , YEAR = 89 , GPS_STATUS = 71
}
 

函数

void operator>> (const YAML::Node &node, std::pair< int, LaserCorrection > &correction)
 
void operator>> (const YAML::Node &node, Calibration &calibration)
 
YAML::Emitter & operator<< (YAML::Emitter &out, const std::pair< int, LaserCorrection > &correction)
 
YAML::Emitter & operator<< (YAML::Emitter &out, const Calibration &calibration)
 
void init_sin_cos_rot_table (float *sin_rot_table, float *cos_rot_table, uint16_t rotation, float rotation_resolution)
 
template<typename T >
void dump_msg (const T &msg, const std::string &file_path)
 
template<class T >
void load_msg (const std::string &file_path, T *msg)
 

变量

constexpr int BLOCKS_PER_PACKET = 12
 
constexpr int BLOCK_SIZE = 100
 Raw Velodyne packet constants and structures.
 
constexpr double PACKET_RATE_VLP16 = 754
 
constexpr double PACKET_RATE_HDL32E = 1808.0
 
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
 
const char * NUM_LASERS = "num_lasers"
 
const char * LASERS = "lasers"
 
const char * LASER_ID = "laser_id"
 
const char * ROT_CORRECTION = "rot_correction"
 
const char * VERT_CORRECTION = "vert_correction"
 
const char * DIST_CORRECTION = "dist_correction"
 
const char * TWO_PT_CORRECTION_AVAILABLE = "two_pt_correction_available"
 
const char * DIST_CORRECTION_X = "dist_correction_x"
 
const char * DIST_CORRECTION_Y = "dist_correction_y"
 
const char * VERT_OFFSET_CORRECTION = "vert_offset_correction"
 
const char * HORIZ_OFFSET_CORRECTION = "horiz_offset_correction"
 
const char * MAX_INTENSITY = "max_intensity"
 
const char * MIN_INTENSITY = "min_intensity"
 
const char * FOCAL_DISTANCE = "focal_distance"
 
const char * FOCAL_SLOPE = "focal_slope"
 
const int ORDER_16 [16] = {0, 2, 4, 6, 8, 10, 12, 14, 1, 3, 5, 7, 9, 11, 13, 15}
 Order array for re-ordering point cloud.
 
const int ORDER_HDL32E [32]
 
const int ORDER_64 [64]
 
const float INNER_TIME_64 [12][32]
 
const float INNER_TIME_64E_S3 [12][32]
 
const float INNER_TIME_HDL32E [12][32]
 
const float INNER_TIME_16 [12][32]
 
const float INNER_TIME_128 [12][32]
 
const float INNER_TIME_VLP32C [12][32]
 
constexpr double DEGRESS_TO_RADIANS = 3.1415926535897 / 180.0
 

类型定义说明

◆ NMEATimePtr

在文件 input.h46 行定义.

枚举类型说明

◆ Mode

枚举值
STRONGEST 
LAST 
DUAL 

在文件 velodyne.proto18 行定义.

◆ Model

枚举值
UNKNOWN 
HDL64E_S3S 
HDL64E_S3D 
HDL64E_S2 
HDL32E 
VLP16 
VLP32C 
VLS128 

在文件 velodyne.proto7 行定义.

◆ StatusType

枚举值
HOURS 
MINUTES 
SECONDS 
DATE 
MONTH 
YEAR 
GPS_STATUS 

在文件 velodyne_parser.h159 行定义.

函数说明

◆ dump_msg()

template<typename T >
void apollo::drivers::velodyne::dump_msg ( const T &  msg,
const std::string &  file_path 
)

在文件 util.h28 行定义.

28 {
29 // std::ofstream ofs(file_path.c_str(),
30 // std::ofstream::out | std::ofstream::binary);
31 // uint32_t serial_size = ros::serialization::serializationLength(msg);
32 // boost::shared_array<uint8_t> obuffer(new uint8_t[serial_size]);
33 // ros::serialization::OStream ostream(obuffer.get(), serial_size);
34 // ros::serialization::serialize(ostream, msg);
35 // ofs.write((char*)obuffer.get(), serial_size);
36 // ofs.close();
37}

◆ init_sin_cos_rot_table()

void apollo::drivers::velodyne::init_sin_cos_rot_table ( float *  sin_rot_table,
float *  cos_rot_table,
uint16_t  rotation,
float  rotation_resolution 
)

在文件 util.cc23 行定义.

24 {
25 for (uint16_t i = 0; i < rotation; ++i) {
26 // float rotation = angles::from_degrees(rotation_resolution * i);
27 float rotation =
28 rotation_resolution * static_cast<float>(i * M_PI) / 180.0f;
29 cos_rot_table[i] = cosf(rotation);
30 sin_rot_table[i] = sinf(rotation);
31 }
32}

◆ load_msg()

template<class T >
void apollo::drivers::velodyne::load_msg ( const std::string &  file_path,
T *  msg 
)

在文件 util.h40 行定义.

40 {
41 // std::ifstream ifs(file_path.c_str(),
42 // std::ifstream::in | std::ifstream::binary);
43 // ifs.seekg(0, std::ios::end);
44 // std::streampos end = ifs.tellg();
45 // ifs.seekg(0, std::ios::beg);
46 // std::streampos begin = ifs.tellg();
47 //
48 // uint32_t file_size = end - begin;
49 // boost::shared_array<uint8_t> ibuffer(new uint8_t[file_size]);
50 // ifs.read((char*)ibuffer.get(), file_size);
51 // ros::serialization::IStream istream(ibuffer.get(), file_size);
52 // ros::serialization::deserialize(istream, *msg);
53 // ifs.close();
54}

◆ operator<<() [1/2]

YAML::Emitter & apollo::drivers::velodyne::operator<< ( YAML::Emitter &  out,
const Calibration calibration 
)

在文件 calibration.cc190 行定义.

190 {
191 out << YAML::BeginMap;
192 out << YAML::Key << NUM_LASERS << YAML::Value
193 << calibration.laser_corrections_.size();
194 out << YAML::Key << LASERS << YAML::Value << YAML::BeginSeq;
195
196 for (std::map<int, LaserCorrection>::const_iterator it =
197 calibration.laser_corrections_.begin();
198 it != calibration.laser_corrections_.end(); ++it) {
199 out << *it;
200 }
201
202 out << YAML::EndSeq;
203 out << YAML::EndMap;
204 return out;
205}
std::map< int, LaserCorrection > laser_corrections_
Definition calibration.h:70

◆ operator<<() [2/2]

YAML::Emitter & apollo::drivers::velodyne::operator<< ( YAML::Emitter &  out,
const std::pair< int, LaserCorrection > &  correction 
)

在文件 calibration.cc160 行定义.

161 {
162 out << YAML::BeginMap;
163 out << YAML::Key << LASER_ID << YAML::Value << correction.first;
164 out << YAML::Key << ROT_CORRECTION << YAML::Value
165 << correction.second.rot_correction;
166 out << YAML::Key << VERT_CORRECTION << YAML::Value
167 << correction.second.vert_correction;
168 out << YAML::Key << DIST_CORRECTION << YAML::Value
169 << correction.second.dist_correction;
170 out << YAML::Key << DIST_CORRECTION_X << YAML::Value
171 << correction.second.dist_correction_x;
172 out << YAML::Key << DIST_CORRECTION_Y << YAML::Value
173 << correction.second.dist_correction_y;
174 out << YAML::Key << VERT_OFFSET_CORRECTION << YAML::Value
175 << correction.second.vert_offset_correction;
176 out << YAML::Key << HORIZ_OFFSET_CORRECTION << YAML::Value
177 << correction.second.horiz_offset_correction;
178 out << YAML::Key << MAX_INTENSITY << YAML::Value
179 << correction.second.max_intensity;
180 out << YAML::Key << MIN_INTENSITY << YAML::Value
181 << correction.second.min_intensity;
182 out << YAML::Key << FOCAL_DISTANCE << YAML::Value
183 << correction.second.focal_distance;
184 out << YAML::Key << FOCAL_SLOPE << YAML::Value
185 << correction.second.focal_slope;
186 out << YAML::EndMap;
187 return out;
188}

◆ operator>>() [1/2]

void apollo::drivers::velodyne::operator>> ( const YAML::Node &  node,
Calibration calibration 
)

在文件 calibration.cc114 行定义.

114 {
115 int num_lasers = 0;
116 node[NUM_LASERS] >> num_lasers;
117 const YAML::Node& lasers = node[LASERS];
118 calibration.laser_corrections_.clear();
119 calibration.num_lasers_ = num_lasers;
120
121 if (static_cast<int>(lasers.size()) != num_lasers) {
122 std::cerr << "num_lasers didn't match";
123 return;
124 }
125
126 for (int i = 0; i < num_lasers; i++) {
127 std::pair<int, LaserCorrection> correction;
128 lasers[i] >> correction;
129 calibration.laser_corrections_.insert(correction);
130 }
131
132 // For each laser ring, find the next-smallest vertical angle.
133 //
134 // This implementation is simple, but not efficient. That is OK,
135 // since it only runs while starting up.
136 double next_angle = -std::numeric_limits<double>::infinity();
137
138 for (int ring = 0; ring < num_lasers; ++ring) {
139 // find minimum remaining vertical offset correction
140 double min_seen = std::numeric_limits<double>::infinity();
141 int next_index = num_lasers;
142
143 for (int j = 0; j < num_lasers; ++j) {
144 double angle = calibration.laser_corrections_[j].vert_correction;
145
146 if (next_angle < angle && angle < min_seen) {
147 min_seen = angle;
148 next_index = j;
149 }
150 }
151
152 if (next_index < num_lasers) { // anything found in this ring?
153 // store this ring number with its corresponding laser number
154 calibration.laser_corrections_[next_index].laser_ring = ring;
155 next_angle = min_seen;
156 }
157 }
158}

◆ operator>>() [2/2]

void apollo::drivers::velodyne::operator>> ( const YAML::Node &  node,
std::pair< int, LaserCorrection > &  correction 
)

在文件 calibration.cc71 行定义.

72 {
73 node[LASER_ID] >> correction.first;
74 node[ROT_CORRECTION] >> correction.second.rot_correction;
75 node[VERT_CORRECTION] >> correction.second.vert_correction;
76 node[DIST_CORRECTION] >> correction.second.dist_correction;
77 node[DIST_CORRECTION_X] >> correction.second.dist_correction_x;
78 node[DIST_CORRECTION_Y] >> correction.second.dist_correction_y;
79 node[VERT_OFFSET_CORRECTION] >> correction.second.vert_offset_correction;
80 if (node[HORIZ_OFFSET_CORRECTION]) {
81 node[HORIZ_OFFSET_CORRECTION] >> correction.second.horiz_offset_correction;
82 } else {
83 correction.second.horiz_offset_correction = 0.0;
84 }
85
86 if (node[MAX_INTENSITY]) {
87 node[MAX_INTENSITY] >> correction.second.max_intensity;
88 } else {
89 correction.second.max_intensity = 255;
90 }
91
92 if (node[MIN_INTENSITY]) {
93 node[MIN_INTENSITY] >> correction.second.min_intensity;
94 } else {
95 correction.second.min_intensity = 0;
96 }
97
98 node[FOCAL_DISTANCE] >> correction.second.focal_distance;
99 node[FOCAL_SLOPE] >> correction.second.focal_slope;
100
101 // Calculate cached values
102 correction.second.cos_rot_correction = cosf(correction.second.rot_correction);
103 correction.second.sin_rot_correction = sinf(correction.second.rot_correction);
104 correction.second.cos_vert_correction =
105 cosf(correction.second.vert_correction);
106 correction.second.sin_vert_correction =
107 sinf(correction.second.vert_correction);
108 correction.second.focal_offset =
109 256.0f * static_cast<float>(std::pow(
110 1 - correction.second.focal_distance / 13100.0f, 2));
111 correction.second.laser_ring = 0; // clear initially (set later)
112}

变量说明

◆ BLOCK_SIZE

static const int apollo::drivers::velodyne::BLOCK_SIZE = 100
constexpr

Raw Velodyne packet constants and structures.

在文件 driver.h34 行定义.

◆ BLOCKS_PER_PACKET

static const int apollo::drivers::velodyne::BLOCKS_PER_PACKET = 12
constexpr

在文件 driver.h33 行定义.

◆ DEGRESS_TO_RADIANS

constexpr double apollo::drivers::velodyne::DEGRESS_TO_RADIANS = 3.1415926535897 / 180.0
constexpr

在文件 online_calibration.h35 行定义.

◆ DIST_CORRECTION

const char* apollo::drivers::velodyne::DIST_CORRECTION = "dist_correction"

在文件 calibration.cc60 行定义.

◆ DIST_CORRECTION_X

const char* apollo::drivers::velodyne::DIST_CORRECTION_X = "dist_correction_x"

在文件 calibration.cc62 行定义.

◆ DIST_CORRECTION_Y

const char* apollo::drivers::velodyne::DIST_CORRECTION_Y = "dist_correction_y"

在文件 calibration.cc63 行定义.

◆ FOCAL_DISTANCE

const char* apollo::drivers::velodyne::FOCAL_DISTANCE = "focal_distance"

在文件 calibration.cc68 行定义.

◆ FOCAL_SLOPE

const char* apollo::drivers::velodyne::FOCAL_SLOPE = "focal_slope"

在文件 calibration.cc69 行定义.

◆ HORIZ_OFFSET_CORRECTION

const char* apollo::drivers::velodyne::HORIZ_OFFSET_CORRECTION = "horiz_offset_correction"

在文件 calibration.cc65 行定义.

◆ INNER_TIME_128

const float apollo::drivers::velodyne::INNER_TIME_128[12][32]

在文件 const_variables.h257 行定义.

257 {
258 {-8.7f, -8.7f, -8.7f, -8.7f, -8.7f, -8.7f, -8.7f, -8.7f,
259 -6.0f, -6.0f, -6.0f, -6.0f, -6.0f, -6.0f, -6.0f, -6.0f,
260 -3.4f, -3.4f, -3.4f, -3.4f, -3.4f, -3.4f, -3.4f, -3.4f,
261 -0.7f, -0.7f, -0.7f, -0.7f, -0.7f, -0.7f, -0.7f, -0.7f},
262 {2.0f, 2.0f, 2.0f, 2.0f, 2.0f, 2.0f, 2.0f, 2.0f, 4.6f, 4.6f, 4.6f,
263 4.6f, 4.6f, 4.6f, 4.6f, 4.6f, 7.3f, 7.3f, 7.3f, 7.3f, 7.3f, 7.3f,
264 7.3f, 7.3f, 10.0f, 10.0f, 10.0f, 10.0f, 10.0f, 10.0f, 10.0f, 10.0f},
265 {15.3f, 15.3f, 15.3f, 15.3f, 15.3f, 15.3f, 15.3f, 15.3f,
266 18.0f, 18.0f, 18.0f, 18.0f, 18.0f, 18.0f, 18.0f, 18.0f,
267 20.6f, 20.6f, 20.6f, 20.6f, 20.6f, 20.6f, 20.6f, 20.6f,
268 23.3f, 23.3f, 23.3f, 23.3f, 23.3f, 23.3f, 23.3f, 23.3f},
269 {25.9f, 25.9f, 25.9f, 25.9f, 25.9f, 25.9f, 25.9f, 25.9f,
270 28.6f, 28.6f, 28.6f, 28.6f, 28.6f, 28.6f, 28.6f, 28.6f,
271 31.3f, 31.3f, 31.3f, 31.3f, 31.3f, 31.3f, 31.3f, 31.3f,
272 33.9f, 33.9f, 33.9f, 33.9f, 33.9f, 33.9f, 33.9f, 33.9f},
273 {44.6f, 44.6f, 44.6f, 44.6f, 44.6f, 44.6f, 44.6f, 44.6f,
274 47.3f, 47.3f, 47.3f, 47.3f, 47.3f, 47.3f, 47.3f, 47.3f,
275 49.9f, 49.9f, 49.9f, 49.9f, 49.9f, 49.9f, 49.9f, 49.9f,
276 52.6f, 52.6f, 52.6f, 52.6f, 52.6f, 52.6f, 52.6f, 52.6f},
277 {55.3f, 55.3f, 55.3f, 55.3f, 55.3f, 55.3f, 55.3f, 55.3f,
278 57.9f, 57.9f, 57.9f, 57.9f, 57.9f, 57.9f, 57.9f, 57.9f,
279 60.6f, 60.6f, 60.6f, 60.6f, 60.6f, 60.6f, 60.6f, 60.6f,
280 63.3f, 63.3f, 63.3f, 63.3f, 63.3f, 63.3f, 63.3f, 63.3f},
281 {68.6f, 68.6f, 68.6f, 68.6f, 68.6f, 68.6f, 68.6f, 68.6f,
282 71.3f, 71.3f, 71.3f, 71.3f, 71.3f, 71.3f, 71.3f, 71.3f,
283 73.9f, 73.9f, 73.9f, 73.9f, 73.9f, 73.9f, 73.9f, 73.9f,
284 76.6f, 76.6f, 76.6f, 76.6f, 76.6f, 76.6f, 76.6f, 76.6f},
285 {79.2f, 79.2f, 79.2f, 79.2f, 79.2f, 79.2f, 79.2f, 79.2f,
286 81.9f, 81.9f, 81.9f, 81.9f, 81.9f, 81.9f, 81.9f, 81.9f,
287 84.6f, 84.9f, 84.9f, 84.9f, 84.9f, 84.9f, 84.9f, 84.9f,
288 87.2f, 87.2f, 87.2f, 87.2f, 87.2f, 87.2f, 87.2f, 87.2f},
289 {97.9f, 97.9f, 97.9f, 97.9f, 97.9f, 97.9f, 97.9f, 97.9f,
290 100.6f, 100.6f, 100.6f, 100.6f, 100.6f, 100.6f, 100.6f, 100.6f,
291 103.2f, 103.2f, 103.2f, 103.2f, 103.2f, 103.2f, 103.2f, 103.2f,
292 105.9f, 105.9f, 105.9f, 105.9f, 105.9f, 105.9f, 105.9f, 105.9f},
293 {108.6f, 108.6f, 108.6f, 108.6f, 108.6f, 108.6f, 108.6f, 108.6f,
294 111.2f, 111.2f, 111.2f, 111.2f, 111.2f, 111.2f, 111.2f, 111.2f,
295 113.9f, 113.9f, 113.9f, 113.9f, 113.9f, 113.9f, 113.9f, 113.9f,
296 116.6f, 116.6f, 116.6f, 116.6f, 116.6f, 116.6f, 116.6f, 116.6f},
297 {121.9f, 121.9f, 121.9f, 121.9f, 121.9f, 121.9f, 121.9f, 121.9f,
298 124.6f, 124.6f, 124.6f, 124.6f, 124.6f, 124.6f, 124.6f, 124.6f,
299 127.2f, 127.2f, 127.2f, 127.2f, 127.2f, 127.2f, 127.2f, 127.2f,
300 129.9f, 129.9f, 129.9f, 129.9f, 129.9f, 129.9f, 129.9f, 129.9f},
301 {132.5f, 132.5f, 132.5f, 132.5f, 132.5f, 132.5f, 132.5f, 132.5f,
302 135.2f, 135.2f, 135.2f, 135.2f, 135.2f, 135.2f, 135.2f, 135.2f,
303 137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f, 137.9f,
304 140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f, 140.5f}};

◆ INNER_TIME_16

const float apollo::drivers::velodyne::INNER_TIME_16[12][32]

在文件 const_variables.h193 行定义.

193 {
194 {-0.0f, -2.3f, -4.61f, -6.91f, -9.22f, -11.52f, -13.82f, -16.13f,
195 -18.43f, -20.74f, -23.04f, -25.34f, -27.65f, -29.95f, -32.26f, -34.56f,
196 -55.3f, -57.6f, -59.9f, -62.21f, -64.51f, -66.82f, -69.12f, -71.42f,
197 -73.73f, -76.03f, -78.34f, -80.64f, -82.94f, -85.25f, -87.55f, -89.86f},
198 {-110.59f, -112.9f, -115.2f, -117.5f, -119.81f, -122.11f, -124.42f,
199 -126.72f, -129.02f, -131.33f, -133.63f, -135.94f, -138.24f, -140.54f,
200 -142.85f, -145.15f, -165.89f, -168.19f, -170.5f, -172.8f, -175.1f,
201 -177.41f, -179.71f, -182.02f, -184.32f, -186.62f, -188.93f, -191.23f,
202 -193.54f, -195.84f, -198.14f, -200.45f},
203 {-221.18f, -223.49f, -225.79f, -228.1f, -230.4f, -232.7f, -235.01f,
204 -237.31f, -239.62f, -241.92f, -244.22f, -246.53f, -248.83f, -251.14f,
205 -253.44f, -255.74f, -276.48f, -278.78f, -281.09f, -283.39f, -285.7f,
206 -288.0f, -290.3f, -292.61f, -294.91f, -297.22f, -299.52f, -301.82f,
207 -304.13f, -306.43f, -308.74f, -311.04f},
208 {-331.78f, -334.08f, -336.38f, -338.69f, -340.99f, -343.3f, -345.6f,
209 -347.9f, -350.21f, -352.51f, -354.82f, -357.12f, -359.42f, -361.73f,
210 -364.03f, -366.34f, -387.07f, -389.38f, -391.68f, -393.98f, -396.29f,
211 -398.59f, -400.9f, -403.2f, -405.5f, -407.81f, -410.11f, -412.42f,
212 -414.72f, -417.02f, -419.33f, -421.63f},
213 {-442.37f, -444.67f, -446.98f, -449.28f, -451.58f, -453.89f, -456.19f,
214 -458.5f, -460.8f, -463.1f, -465.41f, -467.71f, -470.02f, -472.32f,
215 -474.62f, -476.93f, -497.66f, -499.97f, -502.27f, -504.58f, -506.88f,
216 -509.18f, -511.49f, -513.79f, -516.1f, -518.4f, -520.7f, -523.01f,
217 -525.31f, -527.62f, -529.92f, -532.22f},
218 {-552.96f, -555.26f, -557.57f, -559.87f, -562.18f, -564.48f, -566.78f,
219 -569.09f, -571.39f, -573.7f, -576.0f, -578.3f, -580.61f, -582.91f,
220 -585.22f, -587.52f, -608.26f, -610.56f, -612.86f, -615.17f, -617.47f,
221 -619.78f, -622.08f, -624.38f, -626.69f, -628.99f, -631.3f, -633.6f,
222 -635.9f, -638.21f, -640.51f, -642.82f},
223 {-663.55f, -665.86f, -668.16f, -670.46f, -672.77f, -675.07f, -677.38f,
224 -679.68f, -681.98f, -684.29f, -686.59f, -688.9f, -691.2f, -693.5f,
225 -695.81f, -698.11f, -718.85f, -721.15f, -723.46f, -725.76f, -728.06f,
226 -730.37f, -732.67f, -734.98f, -737.28f, -739.58f, -741.89f, -744.19f,
227 -746.5f, -748.8f, -751.1f, -753.41f},
228 {-774.14f, -776.45f, -778.75f, -781.06f, -783.36f, -785.66f, -787.97f,
229 -790.27f, -792.58f, -794.88f, -797.18f, -799.49f, -801.79f, -804.1f,
230 -806.4f, -808.7f, -829.44f, -831.74f, -834.05f, -836.35f, -838.66f,
231 -840.96f, -843.26f, -845.57f, -847.87f, -850.18f, -852.48f, -854.78f,
232 -857.09f, -859.39f, -861.7f, -864.0f},
233 {-884.74f, -887.04f, -889.34f, -891.65f, -893.95f, -896.26f, -898.56f,
234 -900.86f, -903.17f, -905.47f, -907.78f, -910.08f, -912.38f, -914.69f,
235 -916.99f, -919.3f, -940.03f, -942.34f, -944.64f, -946.94f, -949.25f,
236 -951.55f, -953.86f, -956.16f, -958.46f, -960.77f, -963.07f, -965.38f,
237 -967.68f, -969.98f, -972.29f, -974.59f},
238 {-995.33f, -997.63f, -999.94f, -1002.24f, -1004.54f, -1006.85f,
239 -1009.15f, -1011.46f, -1013.76f, -1016.06f, -1018.37f, -1020.67f,
240 -1022.98f, -1025.28f, -1027.58f, -1029.89f, -1050.62f, -1052.93f,
241 -1055.23f, -1057.54f, -1059.84f, -1062.14f, -1064.45f, -1066.75f,
242 -1069.06f, -1071.36f, -1073.66f, -1075.97f, -1078.27f, -1080.58f,
243 -1082.88f, -1085.18f},
244 {-1105.92f, -1108.22f, -1110.53f, -1112.83f, -1115.14f, -1117.44f,
245 -1119.74f, -1122.05f, -1124.35f, -1126.66f, -1128.96f, -1131.26f,
246 -1133.57f, -1135.87f, -1138.18f, -1140.48f, -1161.22f, -1163.52f,
247 -1165.82f, -1168.13f, -1170.43f, -1172.74f, -1175.04f, -1177.34f,
248 -1179.65f, -1181.95f, -1184.26f, -1186.56f, -1188.86f, -1191.17f,
249 -1193.47f, -1195.78f},
250 {-1216.51f, -1218.82f, -1221.12f, -1223.42f, -1225.73f, -1228.03f,
251 -1230.34f, -1232.64f, -1234.94f, -1237.25f, -1239.55f, -1241.86f,
252 -1244.16f, -1246.46f, -1248.77f, -1251.07f, -1271.81f, -1274.11f,
253 -1276.42f, -1278.72f, -1281.02f, -1283.33f, -1285.63f, -1287.94f,
254 -1290.24f, -1292.54f, -1294.85f, -1297.15f, -1299.46f, -1301.76f,
255 -1304.06f, -1306.37f}};

◆ INNER_TIME_64

const float apollo::drivers::velodyne::INNER_TIME_64[12][32]

在文件 const_variables.h42 行定义.

42 {
43 {419.30f, 418.57f, 417.84f, 417.12f, 416.39f, 415.66f, 414.93f, 414.20f,
44 413.48f, 412.75f, 412.02f, 411.29f, 410.56f, 409.84f, 409.11f, 408.38f,
45 407.65f, 406.92f, 406.20f, 405.47f, 404.74f, 404.01f, 403.28f, 402.56f,
46 401.83f, 401.10f, 400.37f, 399.64f, 398.92f, 398.19f, 397.46f, 396.73f},
47 {419.30f, 418.57f, 417.84f, 417.12f, 416.39f, 415.66f, 414.93f, 414.20f,
48 413.48f, 412.75f, 412.02f, 411.29f, 410.56f, 409.84f, 409.11f, 408.38f,
49 407.65f, 406.92f, 406.20f, 405.47f, 404.74f, 404.01f, 403.28f, 402.56f,
50 401.83f, 401.10f, 400.37f, 399.64f, 398.92f, 398.19f, 397.46f, 396.73f},
51 {396.00f, 395.28f, 394.55f, 393.82f, 393.09f, 392.36f, 391.64f, 390.91f,
52 390.18f, 389.45f, 388.72f, 388.00f, 387.27f, 386.54f, 385.81f, 385.08f,
53 384.36f, 383.63f, 382.90f, 382.17f, 381.44f, 380.72f, 379.99f, 379.26f,
54 378.53f, 377.80f, 377.08f, 376.35f, 375.62f, 374.89f, 374.16f, 373.44f},
55 {396.00f, 395.28f, 394.55f, 393.82f, 393.09f, 392.36f, 391.64f, 390.91f,
56 390.18f, 389.45f, 388.72f, 388.00f, 387.27f, 386.54f, 385.81f, 385.08f,
57 384.36f, 383.63f, 382.90f, 382.17f, 381.44f, 380.72f, 379.99f, 379.26f,
58 378.53f, 377.80f, 377.08f, 376.35f, 375.62f, 374.89f, 374.16f, 373.44f},
59 {372.71f, 371.98f, 371.25f, 370.52f, 369.80f, 369.07f, 368.34f, 367.61f,
60 366.88f, 366.16f, 365.43f, 364.70f, 363.97f, 363.24f, 362.52f, 361.79f,
61 361.06f, 360.33f, 359.60f, 358.88f, 358.15f, 357.42f, 356.69f, 355.96f,
62 355.24f, 354.51f, 353.78f, 353.05f, 352.32f, 351.60f, 350.87f, 350.14f},
63 {372.71f, 371.98f, 371.25f, 370.52f, 369.80f, 369.07f, 368.34f, 367.61f,
64 366.88f, 366.16f, 365.43f, 364.70f, 363.97f, 363.24f, 362.52f, 361.79f,
65 361.06f, 360.33f, 359.60f, 358.88f, 358.15f, 357.42f, 356.69f, 355.96f,
66 355.24f, 354.51f, 353.78f, 353.05f, 352.32f, 351.60f, 350.87f, 350.14f},
67 {349.41f, 348.68f, 347.96f, 347.23f, 346.50f, 345.77f, 345.04f, 344.32f,
68 343.59f, 342.86f, 342.13f, 341.40f, 340.68f, 339.95f, 339.22f, 338.49f,
69 337.76f, 337.04f, 336.31f, 335.58f, 334.85f, 334.12f, 333.40f, 332.67f,
70 331.94f, 331.21f, 330.48f, 329.76f, 329.03f, 328.30f, 327.57f, 326.84f},
71 {349.41f, 348.68f, 347.96f, 347.23f, 346.50f, 345.77f, 345.04f, 344.32f,
72 343.59f, 342.86f, 342.13f, 341.40f, 340.68f, 339.95f, 339.22f, 338.49f,
73 337.76f, 337.04f, 336.31f, 335.58f, 334.85f, 334.12f, 333.40f, 332.67f,
74 331.94f, 331.21f, 330.48f, 329.76f, 329.03f, 328.30f, 327.57f, 326.84f},
75 {326.12f, 325.39f, 324.66f, 323.93f, 323.20f, 322.48f, 321.75f, 321.02f,
76 320.29f, 319.56f, 318.84f, 318.11f, 317.38f, 316.65f, 315.92f, 315.20f,
77 314.47f, 313.74f, 313.01f, 312.28f, 311.56f, 310.83f, 310.10f, 309.37f,
78 308.64f, 307.92f, 307.19f, 306.46f, 305.73f, 305.00f, 304.28f, 303.55f},
79 {326.12f, 325.39f, 324.66f, 323.93f, 323.20f, 322.48f, 321.75f, 321.02f,
80 320.29f, 319.56f, 318.84f, 318.11f, 317.38f, 316.65f, 315.92f, 315.20f,
81 314.47f, 313.74f, 313.01f, 312.28f, 311.56f, 310.83f, 310.10f, 309.37f,
82 308.64f, 307.92f, 307.19f, 306.46f, 305.73f, 305.00f, 304.28f, 303.55f},
83 {302.82f, 302.09f, 301.36f, 300.64f, 299.91f, 299.18f, 298.45f, 297.72f,
84 297.00f, 296.27f, 295.54f, 294.81f, 294.08f, 293.36f, 292.63f, 291.90f,
85 291.17f, 290.44f, 289.72f, 288.99f, 288.26f, 287.53f, 286.80f, 286.08f,
86 285.35f, 284.62f, 283.89f, 283.16f, 282.44f, 281.71f, 280.98f, 280.25f},
87 {302.82f, 302.09f, 301.36f, 300.64f, 299.91f, 299.18f, 298.45f, 297.72f,
88 297.00f, 296.27f, 295.54f, 294.81f, 294.08f, 293.36f, 292.63f, 291.90f,
89 291.17f, 290.44f, 289.72f, 288.99f, 288.26f, 287.53f, 286.80f, 286.08f,
90 285.35f, 284.62f, 283.89f, 283.16f, 282.44f, 281.71f, 280.98f, 280.25f}};

◆ INNER_TIME_64E_S3

const float apollo::drivers::velodyne::INNER_TIME_64E_S3[12][32]

在文件 const_variables.h92 行定义.

92 {
93 {172.8f, 171.5f, 170.3f, 169.1f, 165.6f, 164.3f, 163.1f, 161.9f,
94 158.4f, 157.1f, 155.9f, 154.7f, 151.2f, 149.9f, 148.7f, 147.5f,
95 144.0f, 142.7f, 141.5f, 140.3f, 136.8f, 135.5f, 134.3f, 133.1f,
96 129.6f, 128.3f, 127.1f, 125.9f, 122.4f, 121.1f, 119.9f, 118.7f},
97 {172.8f, 171.5f, 170.3f, 169.1f, 165.6f, 164.3f, 163.1f, 161.9f,
98 158.4f, 157.1f, 155.9f, 154.7f, 151.2f, 149.9f, 148.7f, 147.5f,
99 144.0f, 142.7f, 141.5f, 140.3f, 136.8f, 135.5f, 134.3f, 133.1f,
100 129.6f, 128.3f, 127.1f, 125.9f, 122.4f, 121.1f, 119.9f, 118.7f},
101 {172.8f, 171.5f, 170.3f, 169.1f, 165.6f, 164.3f, 163.1f, 161.9f,
102 158.4f, 157.1f, 155.9f, 154.7f, 151.2f, 149.9f, 148.7f, 147.5f,
103 144.0f, 142.7f, 141.5f, 140.3f, 136.8f, 135.5f, 134.3f, 133.1f,
104 129.6f, 128.3f, 127.1f, 125.9f, 122.4f, 121.1f, 119.9f, 118.7f},
105 {172.8f, 171.5f, 170.3f, 169.1f, 165.6f, 164.3f, 163.1f, 161.9f,
106 158.4f, 157.1f, 155.9f, 154.7f, 151.2f, 149.9f, 148.7f, 147.5f,
107 144.0f, 142.7f, 141.5f, 140.3f, 136.8f, 135.5f, 134.3f, 133.1f,
108 129.6f, 128.3f, 127.1f, 125.9f, 122.4f, 121.1f, 119.9f, 118.7f},
109 {115.2f, 113.9f, 112.7f, 111.5f, 108.0f, 106.7f, 105.5f, 104.3f,
110 100.8f, 99.5f, 98.3f, 97.1f, 93.6f, 92.3f, 91.1f, 89.9f,
111 86.4f, 85.1f, 83.9f, 82.7f, 79.2f, 77.9f, 76.7f, 75.5f,
112 72.0f, 70.7f, 69.5f, 68.3f, 64.8f, 63.5f, 62.3f, 61.1f},
113 {115.2f, 113.9f, 112.7f, 111.5f, 108.0f, 106.7f, 105.5f, 104.3f,
114 100.8f, 99.5f, 98.3f, 97.1f, 93.6f, 92.3f, 91.1f, 89.9f,
115 86.4f, 85.1f, 83.9f, 82.7f, 79.2f, 77.9f, 76.7f, 75.5f,
116 72.0f, 70.7f, 69.5f, 68.3f, 64.8f, 63.5f, 62.3f, 61.1f},
117 {115.2f, 113.9f, 112.7f, 111.5f, 108.0f, 106.7f, 105.5f, 104.3f,
118 100.8f, 99.5f, 98.3f, 97.1f, 93.6f, 92.3f, 91.1f, 89.9f,
119 86.4f, 85.1f, 83.9f, 82.7f, 79.2f, 77.9f, 76.7f, 75.5f,
120 72.0f, 70.7f, 69.5f, 68.3f, 64.8f, 63.5f, 62.3f, 61.1f},
121 {115.2f, 113.9f, 112.7f, 111.5f, 108.0f, 106.7f, 105.5f, 104.3f,
122 100.8f, 99.5f, 98.3f, 97.1f, 93.6f, 92.3f, 91.1f, 89.9f,
123 86.4f, 85.1f, 83.9f, 82.7f, 79.2f, 77.9f, 76.7f, 75.5f,
124 72.0f, 70.7f, 69.5f, 68.3f, 64.8f, 63.5f, 62.3f, 61.1f},
125 {57.6f, 56.3f, 55.1f, 53.9f, 50.4f, 49.1f, 47.9f, 46.7f,
126 43.2f, 41.9f, 40.7f, 39.5f, 36.0f, 34.7f, 33.5f, 32.3f,
127 28.8f, 27.5f, 26.3f, 25.1f, 21.6f, 20.3f, 19.1f, 17.9f,
128 14.4f, 13.1f, 11.9f, 10.7f, 7.2f, 5.9f, 4.7f, 3.5f},
129 {57.6f, 56.3f, 55.1f, 53.9f, 50.4f, 49.1f, 47.9f, 46.7f,
130 43.2f, 41.9f, 40.7f, 39.5f, 36.0f, 34.7f, 33.5f, 32.3f,
131 28.8f, 27.5f, 26.3f, 25.1f, 21.6f, 20.3f, 19.1f, 17.9f,
132 14.4f, 13.1f, 11.9f, 10.7f, 7.2f, 5.9f, 4.7f, 3.5f},
133 {57.6f, 56.3f, 55.1f, 53.9f, 50.4f, 49.1f, 47.9f, 46.7f,
134 43.2f, 41.9f, 40.7f, 39.5f, 36.0f, 34.7f, 33.5f, 32.3f,
135 28.8f, 27.5f, 26.3f, 25.1f, 21.6f, 20.3f, 19.1f, 17.9f,
136 14.4f, 13.1f, 11.9f, 10.7f, 7.2f, 5.9f, 4.7f, 3.5f},
137 {57.6f, 56.3f, 55.1f, 53.9f, 50.4f, 49.1f, 47.9f, 46.7f,
138 43.2f, 41.9f, 40.7f, 39.5f, 36.0f, 34.7f, 33.5f, 32.3f,
139 28.8f, 27.5f, 26.3f, 25.1f, 21.6f, 20.3f, 19.1f, 17.9f,
140 14.4f, 13.1f, 11.9f, 10.7f, 7.2f, 5.9f, 4.7f, 3.5f}};

◆ INNER_TIME_HDL32E

const float apollo::drivers::velodyne::INNER_TIME_HDL32E[12][32]

在文件 const_variables.h143 行定义.

143 {
144 {543.0f, 541.0f, 540.0f, 539.0f, 538.0f, 537.0f, 536.0f, 535.0f,
145 533.0f, 532.0f, 531.0f, 530.0f, 529.0f, 528.0f, 526.0f, 525.0f,
146 524.0f, 523.0f, 522.0f, 521.0f, 520.0f, 518.0f, 517.0f, 516.0f,
147 515.0f, 514.0f, 513.0f, 511.0f, 510.0f, 509.0f, 508.0f, 507.0f},
148 {497.0f, 495.0f, 494.0f, 493.0f, 492.0f, 491.0f, 490.0f, 488.0f,
149 487.0f, 486.0f, 485.0f, 484.0f, 483.0f, 482.0f, 480.0f, 479.0f,
150 478.0f, 477.0f, 476.0f, 475.0f, 473.0f, 472.0f, 471.0f, 470.0f,
151 469.0f, 468.0f, 467.0f, 465.0f, 464.0f, 463.0f, 462.0f, 461.0f},
152 {450.0f, 449.0f, 448.0f, 447.0f, 446.0f, 445.0f, 444.0f, 442.0f,
153 441.0f, 440.0f, 439.0f, 438.0f, 437.0f, 435.0f, 434.0f, 433.0f,
154 432.0f, 431.0f, 430.0f, 429.0f, 427.0f, 426.0f, 425.0f, 424.0f,
155 423.0f, 422.0f, 420.0f, 419.0f, 418.0f, 417.0f, 416.0f, 415.0f},
156 {404.0f, 403.0f, 402.0f, 401.0f, 400.0f, 399.0f, 397.0f, 396.0f,
157 395.0f, 394.0f, 393.0f, 392.0f, 391.0f, 389.0f, 388.0f, 387.0f,
158 386.0f, 385.0f, 384.0f, 382.0f, 381.0f, 380.0f, 379.0f, 378.0f,
159 377.0f, 376.0f, 374.0f, 373.0f, 372.0f, 371.0f, 370.0f, 369.0f},
160 {358.0f, 357.0f, 356.0f, 355.0f, 354.0f, 353.0f, 351.0f, 350.0f,
161 349.0f, 348.0f, 347.0f, 346.0f, 344.0f, 343.0f, 342.0f, 341.0f,
162 340.0f, 339.0f, 338.0f, 336.0f, 335.0f, 334.0f, 333.0f, 332.0f,
163 331.0f, 329.0f, 328.0f, 327.0f, 326.0f, 325.0f, 324.0f, 323.0f},
164 {312.0f, 311.0f, 310.0f, 309.0f, 308.0f, 306.0f, 305.0f, 304.0f,
165 303.0f, 302.0f, 301.0f, 300.0f, 298.0f, 297.0f, 296.0f, 295.0f,
166 294.0f, 293.0f, 291.0f, 290.0f, 289.0f, 288.0f, 287.0f, 286.0f,
167 285.0f, 283.0f, 282.0f, 281.0f, 280.0f, 279.0f, 278.0f, 276.0f},
168 {266.0f, 265.0f, 264.0f, 263.0f, 262.0f, 260.0f, 259.0f, 258.0f,
169 257.0f, 256.0f, 255.0f, 253.0f, 252.0f, 251.0f, 250.0f, 249.0f,
170 248.0f, 247.0f, 245.0f, 244.0f, 243.0f, 242.0f, 241.0f, 240.0f,
171 238.0f, 237.0f, 236.0f, 235.0f, 234.0f, 233.0f, 232.0f, 230.0f},
172 {220.0f, 219.0f, 218.0f, 217.0f, 215.0f, 214.0f, 213.0f, 212.0f,
173 211.0f, 210.0f, 209.0f, 207.0f, 206.0f, 205.0f, 204.0f, 203.0f,
174 202.0f, 200.0f, 199.0f, 198.0f, 197.0f, 196.0f, 195.0f, 194.0f,
175 192.0f, 191.0f, 190.0f, 189.0f, 188.0f, 187.0f, 185.0f, 184.0f},
176 {174.0f, 173.0f, 172.0f, 170.0f, 169.0f, 168.0f, 167.0f, 166.0f,
177 165.0f, 164.0f, 162.0f, 161.0f, 160.0f, 159.0f, 158.0f, 157.0f,
178 156.0f, 154.0f, 153.0f, 152.0f, 151.0f, 150.0f, 149.0f, 147.0f,
179 146.0f, 145.0f, 144.0f, 143.0f, 142.0f, 141.0f, 139.0f, 138.0f},
180 {128.0f, 127.0f, 126.0f, 124.0f, 123.0f, 122.0f, 121.0f, 120.0f,
181 119.0f, 118.0f, 116.0f, 115.0f, 114.0f, 113.0f, 112.0f, 111.0f,
182 109.0f, 108.0f, 107.0f, 106.0f, 105.0f, 104.0f, 103.0f, 101.0f,
183 100.0f, 99.0f, 98.0f, 97.0f, 96.0f, 94.0f, 93.0f, 92.0f},
184 {82.0f, 81.0f, 79.0f, 78.0f, 77.0f, 76.0f, 75.0f, 74.0f,
185 73.0f, 71.0f, 70.0f, 69.0f, 68.0f, 67.0f, 66.0f, 65.0f,
186 63.0f, 62.0f, 61.0f, 60.0f, 59.0f, 58.0f, 56.0f, 55.0f,
187 54.0f, 53.0f, 52.0f, 51.0f, 50.0f, 48.0f, 47.0f, 46.0f},
188 {36.0f, 35.0f, 33.0f, 32.0f, 31.0f, 30.0f, 29.0f, 28.0f,
189 26.0f, 25.0f, 24.0f, 23.0f, 22.0f, 21.0f, 20.0f, 18.0f,
190 17.0f, 16.0f, 15.0f, 14.0f, 13.0f, 12.0f, 10.0f, 9.0f,
191 8.0f, 7.0f, 6.0f, 5.0f, 3.0f, 2.0f, 1.0f, 0.0f}};

◆ INNER_TIME_VLP32C

const float apollo::drivers::velodyne::INNER_TIME_VLP32C[12][32]

在文件 const_variables.h306 行定义.

306 {
307 {0.000f, 0.000f, 2.304f, 2.304f, 4.608f, 4.608f, 6.912f, 6.912f,
308 9.216f, 9.216f, 11.520f, 11.520f, 13.824f, 13.824f, 16.128f, 16.128f,
309 18.432f, 18.432f, 20.736f, 20.736f, 23.040f, 23.040f, 25.344f, 25.344f,
310 27.648f, 27.648f, 29.952f, 29.952f, 32.256f, 32.256f, 34.560f, 34.560f},
311 {0.000f, 0.000f, 2.304f, 2.304f, 4.608f, 4.608f, 6.912f, 6.912f,
312 9.216f, 9.216f, 11.520f, 11.520f, 13.824f, 13.824f, 16.128f, 16.128f,
313 18.432f, 18.432f, 20.736f, 20.736f, 23.040f, 23.040f, 25.344f, 25.344f,
314 27.648f, 27.648f, 29.952f, 29.952f, 32.256f, 32.256f, 34.560f, 34.560f},
315 {55.296f, 55.296f, 57.600f, 57.600f, 59.904f, 59.904f, 62.208f, 62.208f,
316 64.512f, 64.512f, 66.816f, 66.816f, 69.120f, 69.120f, 71.424f, 71.424f,
317 73.728f, 73.728f, 76.032f, 76.032f, 78.336f, 78.336f, 80.640f, 80.640f,
318 82.944f, 82.944f, 85.248f, 85.248f, 87.552f, 87.552f, 89.856f, 89.856f},
319 {55.296f, 55.296f, 57.600f, 57.600f, 59.904f, 59.904f, 62.208f, 62.208f,
320 64.512f, 64.512f, 66.816f, 66.816f, 69.120f, 69.120f, 71.424f, 71.424f,
321 73.728f, 73.728f, 76.032f, 76.032f, 78.336f, 78.336f, 80.640f, 80.640f,
322 82.944f, 82.944f, 85.248f, 85.248f, 87.552f, 87.552f, 89.856f, 89.856f},
323 {110.592f, 110.592f, 112.896f, 112.896f, 115.200f, 115.200f, 117.504f,
324 117.504f, 119.808f, 119.808f, 122.112f, 122.112f, 124.416f, 124.416f,
325 126.720f, 126.720f, 129.024f, 129.024f, 131.328f, 131.328f, 133.632f,
326 133.632f, 135.936f, 135.936f, 138.240f, 138.240f, 140.544f, 140.544f,
327 142.848f, 142.848f, 145.152f, 145.152f},
328 {110.592f, 110.592f, 112.896f, 112.896f, 115.200f, 115.200f, 117.504f,
329 117.504f, 119.808f, 119.808f, 122.112f, 122.112f, 124.416f, 124.416f,
330 126.720f, 126.720f, 129.024f, 129.024f, 131.328f, 131.328f, 133.632f,
331 133.632f, 135.936f, 135.936f, 138.240f, 138.240f, 140.544f, 140.544f,
332 142.848f, 142.848f, 145.152f, 145.152f},
333 {165.888f, 165.888f, 168.192f, 168.192f, 170.496f, 170.496f, 172.800f,
334 172.800f, 175.104f, 175.104f, 177.408f, 177.408f, 179.712f, 179.712f,
335 182.016f, 182.016f, 184.320f, 184.320f, 186.624f, 186.624f, 188.928f,
336 188.928f, 191.232f, 191.232f, 193.536f, 193.536f, 195.840f, 195.840f,
337 198.144f, 198.144f, 200.448f, 200.448f},
338 {165.888f, 165.888f, 168.192f, 168.192f, 170.496f, 170.496f, 172.800f,
339 172.800f, 175.104f, 175.104f, 177.408f, 177.408f, 179.712f, 179.712f,
340 182.016f, 182.016f, 184.320f, 184.320f, 186.624f, 186.624f, 188.928f,
341 188.928f, 191.232f, 191.232f, 193.536f, 193.536f, 195.840f, 195.840f,
342 198.144f, 198.144f, 200.448f, 200.448f},
343 {221.184f, 221.184f, 223.488f, 223.488f, 225.792f, 225.792f, 228.096f,
344 228.096f, 230.400f, 230.400f, 232.704f, 232.704f, 235.008f, 235.008f,
345 237.312f, 237.312f, 239.616f, 239.616f, 241.920f, 241.920f, 244.224f,
346 244.224f, 246.528f, 246.528f, 248.832f, 248.832f, 251.136f, 251.136f,
347 253.440f, 253.440f, 255.744f, 255.744f},
348 {221.184f, 221.184f, 223.488f, 223.488f, 225.792f, 225.792f, 228.096f,
349 228.096f, 230.400f, 230.400f, 232.704f, 232.704f, 235.008f, 235.008f,
350 237.312f, 237.312f, 239.616f, 239.616f, 241.920f, 241.920f, 244.224f,
351 244.224f, 246.528f, 246.528f, 248.832f, 248.832f, 251.136f, 251.136f,
352 253.440f, 253.440f, 255.744f, 255.744f},
353 {276.480f, 276.480f, 278.784f, 278.784f, 281.088f, 281.088f, 283.392f,
354 283.392f, 285.696f, 285.696f, 288.000f, 288.000f, 290.304f, 290.304f,
355 292.608f, 292.608f, 294.912f, 294.912f, 297.216f, 297.216f, 299.520f,
356 299.520f, 301.824f, 301.824f, 304.128f, 304.128f, 306.432f, 306.432f,
357 308.736f, 308.736f, 311.040f, 311.040f},
358 {276.480f, 276.480f, 278.784f, 278.784f, 281.088f, 281.088f, 283.392f,
359 283.392f, 285.696f, 285.696f, 288.000f, 288.000f, 290.304f, 290.304f,
360 292.608f, 292.608f, 294.912f, 294.912f, 297.216f, 297.216f, 299.520f,
361 299.520f, 301.824f, 301.824f, 304.128f, 304.128f, 306.432f, 306.432f,
362 308.736f, 308.736f, 311.040f, 311.040f}};

◆ LASER_ID

const char* apollo::drivers::velodyne::LASER_ID = "laser_id"

在文件 calibration.cc57 行定义.

◆ LASERS

const char* apollo::drivers::velodyne::LASERS = "lasers"

在文件 calibration.cc56 行定义.

◆ MAX_INTENSITY

const char* apollo::drivers::velodyne::MAX_INTENSITY = "max_intensity"

在文件 calibration.cc66 行定义.

◆ MIN_INTENSITY

const char* apollo::drivers::velodyne::MIN_INTENSITY = "min_intensity"

在文件 calibration.cc67 行定义.

◆ NUM_LASERS

const char* apollo::drivers::velodyne::NUM_LASERS = "num_lasers"

在文件 calibration.cc55 行定义.

◆ ORDER_16

const int apollo::drivers::velodyne::ORDER_16[16] = {0, 2, 4, 6, 8, 10, 12, 14, 1, 3, 5, 7, 9, 11, 13, 15}

Order array for re-ordering point cloud.

Refer to Velodyne official manual

在文件 const_variables.h29 行定义.

29{0, 2, 4, 6, 8, 10, 12, 14, 1, 3, 5, 7, 9, 11, 13, 15};

◆ ORDER_64

const int apollo::drivers::velodyne::ORDER_64[64]
初始值:
= {38, 39, 42, 43, 32, 33, 36, 37, 40, 41, 46, 47, 50,
51, 54, 55, 44, 45, 48, 49, 52, 53, 58, 59, 62, 63,
34, 35, 56, 57, 60, 61, 6, 7, 10, 11, 0, 1, 4,
5, 8, 9, 14, 15, 18, 19, 22, 23, 12, 13, 16, 17,
20, 21, 26, 27, 30, 31, 2, 3, 24, 25, 28, 29}

在文件 const_variables.h35 行定义.

35 {38, 39, 42, 43, 32, 33, 36, 37, 40, 41, 46, 47, 50,
36 51, 54, 55, 44, 45, 48, 49, 52, 53, 58, 59, 62, 63,
37 34, 35, 56, 57, 60, 61, 6, 7, 10, 11, 0, 1, 4,
38 5, 8, 9, 14, 15, 18, 19, 22, 23, 12, 13, 16, 17,
39 20, 21, 26, 27, 30, 31, 2, 3, 24, 25, 28, 29};

◆ ORDER_HDL32E

const int apollo::drivers::velodyne::ORDER_HDL32E[32]
初始值:
= {0, 2, 4, 6, 8, 10, 12, 14, 16, 18, 20,
22, 24, 26, 28, 30, 1, 3, 5, 7, 9, 11,
13, 15, 17, 19, 21, 23, 25, 27, 29, 31}

在文件 const_variables.h31 行定义.

31 {0, 2, 4, 6, 8, 10, 12, 14, 16, 18, 20,
32 22, 24, 26, 28, 30, 1, 3, 5, 7, 9, 11,
33 13, 15, 17, 19, 21, 23, 25, 27, 29, 31};

◆ PACKET_RATE_HDL32E

constexpr double apollo::drivers::velodyne::PACKET_RATE_HDL32E = 1808.0
constexpr

在文件 driver.h37 行定义.

◆ PACKET_RATE_HDL64E_S2

constexpr double apollo::drivers::velodyne::PACKET_RATE_HDL64E_S2 = 3472.17
constexpr

在文件 driver.h38 行定义.

◆ PACKET_RATE_HDL64E_S3D

constexpr double apollo::drivers::velodyne::PACKET_RATE_HDL64E_S3D = 5789
constexpr

在文件 driver.h40 行定义.

◆ PACKET_RATE_HDL64E_S3S

constexpr double apollo::drivers::velodyne::PACKET_RATE_HDL64E_S3S = 3472.17
constexpr

在文件 driver.h39 行定义.

◆ PACKET_RATE_VLP16

constexpr double apollo::drivers::velodyne::PACKET_RATE_VLP16 = 754
constexpr

在文件 driver.h36 行定义.

◆ PACKET_RATE_VLP32C

constexpr double apollo::drivers::velodyne::PACKET_RATE_VLP32C = 1507.0
constexpr

在文件 driver.h42 行定义.

◆ PACKET_RATE_VLS128

constexpr double apollo::drivers::velodyne::PACKET_RATE_VLS128 = 6250.0
constexpr

在文件 driver.h41 行定义.

◆ ROT_CORRECTION

const char* apollo::drivers::velodyne::ROT_CORRECTION = "rot_correction"

在文件 calibration.cc58 行定义.

◆ TWO_PT_CORRECTION_AVAILABLE

const char* apollo::drivers::velodyne::TWO_PT_CORRECTION_AVAILABLE = "two_pt_correction_available"

在文件 calibration.cc61 行定义.

◆ VERT_CORRECTION

const char* apollo::drivers::velodyne::VERT_CORRECTION = "vert_correction"

在文件 calibration.cc59 行定义.

◆ VERT_OFFSET_CORRECTION

const char* apollo::drivers::velodyne::VERT_OFFSET_CORRECTION = "vert_offset_correction"

在文件 calibration.cc64 行定义.