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

class  Calibration
 Calibration class storing entire configuration for the Lslidar 更多...
 
class  Convert
 
struct  Firing
 
struct  Firing_LS128S2
 
struct  FiringC32
 Raw Lslidar packet. 更多...
 
union  four_bytes
 
struct  LaserCorrection
 correction values for a single laser 更多...
 
class  Lslidar16Parser
 
class  Lslidar32Parser
 
class  Lslidar401Parser
 
class  LslidarCH120Parser
 
class  LslidarCH128Parser
 
class  LslidarCH128X1Parser
 
class  LslidarCH16Parser
 
class  LslidarCH32Parser
 
class  LslidarCH64Parser
 
class  LslidarCH64wParser
 
class  LslidarCXV4Parser
 
class  LslidarLS128S2Parser
 
class  LslidarParser
 Lslidar data conversion class 更多...
 
class  LslidarParserFactory
 
struct  Point
 
struct  Point_LS128S2
 
struct  raw_block
 Raw Lslidar data block. 更多...
 
struct  raw_packet
 
struct  RawBlock
 
struct  RawPacket
 
struct  RawPacket_C32
 
struct  RawPacket_LS128S2
 
union  two_bytes
 used for unpacking the first two data bytes in a block 更多...
 
union  TwoBytes
 
union  vertical_point
 

类型定义

typedef struct apollo::drivers::lslidar::parser::raw_block raw_block_t
 Raw Lslidar data block.
 
typedef struct apollo::drivers::lslidar::parser::FiringC32 FiringC32
 Raw Lslidar packet.
 
typedef struct apollo::drivers::lslidar::parser::raw_packet raw_packet_t
 

函数

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)
 

变量

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"
 
float R1_ = 0.04376
 
float R2_ = 0.010875
 
const int ORDER_16 [16] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15}
 
const int ORDER_32 [32]
 

类型定义说明

◆ FiringC32

Raw Lslidar packet.

revolution is described in the device manual as incrementing (mod 65536) for each physical turn of the device. Our device seems to alternate between two different values every third packet. One value increases, the other decreases.

status has either a temperature encoding or the microcode level

◆ raw_block_t

Raw Lslidar data block.

Each block contains data from either the upper or lower laser bank. The device returns three times as many upper bank blocks.

use cstdint types, so things work with both 64 and 32-bit machines

◆ raw_packet_t

函数说明

◆ operator<<() [1/2]

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

在文件 calibration.cc183 行定义.

183 {
184 out << YAML::BeginMap;
185 out << YAML::Key << NUM_LASERS << YAML::Value
186 << calibration.laser_corrections_.size();
187 out << YAML::Key << LASERS << YAML::Value << YAML::BeginSeq;
188
189 for (std::map<int, LaserCorrection>::const_iterator it
190 = calibration.laser_corrections_.begin();
191 it != calibration.laser_corrections_.end();
192 ++it) {
193 out << *it;
194 }
195
196 out << YAML::EndSeq;
197 out << YAML::EndMap;
198 return out;
199}
std::map< int, LaserCorrection > laser_corrections_
Definition calibration.h:72

◆ operator<<() [2/2]

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

在文件 calibration.cc152 行定义.

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

◆ operator>>() [1/2]

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

在文件 calibration.cc111 行定义.

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

◆ operator>>() [2/2]

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

在文件 calibration.cc64 行定义.

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

变量说明

◆ DIST_CORRECTION

const char* apollo::drivers::lslidar::parser::DIST_CORRECTION = "dist_correction"

在文件 calibration.cc53 行定义.

◆ DIST_CORRECTION_X

const char* apollo::drivers::lslidar::parser::DIST_CORRECTION_X = "dist_correction_x"

在文件 calibration.cc55 行定义.

◆ DIST_CORRECTION_Y

const char* apollo::drivers::lslidar::parser::DIST_CORRECTION_Y = "dist_correction_y"

在文件 calibration.cc56 行定义.

◆ FOCAL_DISTANCE

const char* apollo::drivers::lslidar::parser::FOCAL_DISTANCE = "focal_distance"

在文件 calibration.cc61 行定义.

◆ FOCAL_SLOPE

const char* apollo::drivers::lslidar::parser::FOCAL_SLOPE = "focal_slope"

在文件 calibration.cc62 行定义.

◆ HORIZ_OFFSET_CORRECTION

const char* apollo::drivers::lslidar::parser::HORIZ_OFFSET_CORRECTION = "horiz_offset_correction"

在文件 calibration.cc58 行定义.

◆ LASER_ID

const char* apollo::drivers::lslidar::parser::LASER_ID = "laser_id"

在文件 calibration.cc50 行定义.

◆ LASERS

const char* apollo::drivers::lslidar::parser::LASERS = "lasers"

在文件 calibration.cc49 行定义.

◆ MAX_INTENSITY

const char* apollo::drivers::lslidar::parser::MAX_INTENSITY = "max_intensity"

在文件 calibration.cc59 行定义.

◆ MIN_INTENSITY

const char* apollo::drivers::lslidar::parser::MIN_INTENSITY = "min_intensity"

在文件 calibration.cc60 行定义.

◆ NUM_LASERS

const char* apollo::drivers::lslidar::parser::NUM_LASERS = "num_lasers"

在文件 calibration.cc48 行定义.

◆ ORDER_16

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

在文件 lslidar_parser.h174 行定义.

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

◆ ORDER_32

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

在文件 lslidar_parser.h175 行定义.

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

◆ R1_

float apollo::drivers::lslidar::parser::R1_ = 0.04376

在文件 lslidar16_parser.cc24 行定义.

◆ R2_

float apollo::drivers::lslidar::parser::R2_ = 0.010875

在文件 lslidar16_parser.cc25 行定义.

◆ ROT_CORRECTION

const char* apollo::drivers::lslidar::parser::ROT_CORRECTION = "rot_correction"

在文件 calibration.cc51 行定义.

◆ TWO_PT_CORRECTION_AVAILABLE

const char* apollo::drivers::lslidar::parser::TWO_PT_CORRECTION_AVAILABLE = "two_pt_correction_available"

在文件 calibration.cc54 行定义.

◆ VERT_CORRECTION

const char* apollo::drivers::lslidar::parser::VERT_CORRECTION = "vert_correction"

在文件 calibration.cc52 行定义.

◆ VERT_OFFSET_CORRECTION

const char* apollo::drivers::lslidar::parser::VERT_OFFSET_CORRECTION = "vert_offset_correction"

在文件 calibration.cc57 行定义.