19 #include <yaml-cpp/yaml.h> 21 #ifdef HAVE_NEW_YAMLCPP 31 #endif // HAVE_NEW_YAMLCPP 47 "two_pt_correction_available";
59 std::pair<int, LaserCorrection>& correction)
65 #ifdef HAVE_NEW_YAMLCPP 66 if (node[TWO_PT_CORRECTION_AVAILABLE])
68 correction.second.two_pt_correction_available;
70 if (
const YAML::Node *pName = node.FindValue(TWO_PT_CORRECTION_AVAILABLE))
71 *pName >> correction.second.two_pt_correction_available;
74 correction.second.two_pt_correction_available =
false;
75 node[DIST_CORRECTION_X] >> correction.second.dist_correction_x;
76 node[DIST_CORRECTION_Y] >> correction.second.dist_correction_y;
77 node[VERT_OFFSET_CORRECTION] >> correction.second.vert_offset_correction;
78 #ifdef HAVE_NEW_YAMLCPP
79 if (node[HORIZ_OFFSET_CORRECTION])
81 correction.second.horiz_offset_correction;
83 if (
const YAML::Node *pName = node.FindValue(HORIZ_OFFSET_CORRECTION))
84 *pName >> correction.second.horiz_offset_correction;
87 correction.second.horiz_offset_correction = 0;
89 const YAML::Node * max_intensity_node = NULL;
90 #ifdef HAVE_NEW_YAMLCPP
91 if (node[MAX_INTENSITY]) {
92 const YAML::Node max_intensity_node_ref = node[
MAX_INTENSITY];
93 max_intensity_node = &max_intensity_node_ref;
96 if (
const YAML::Node *pName = node.FindValue(MAX_INTENSITY))
97 max_intensity_node = pName;
99 if (max_intensity_node) {
100 float max_intensity_float;
101 *max_intensity_node >> max_intensity_float;
102 correction.second.max_intensity = floor(max_intensity_float);
105 correction.second.max_intensity = 255;
108 const YAML::Node * min_intensity_node = NULL;
109 #ifdef HAVE_NEW_YAMLCPP 110 if (node[MIN_INTENSITY]) {
111 const YAML::Node min_intensity_node_ref = node[
MIN_INTENSITY];
112 min_intensity_node = &min_intensity_node_ref;
115 if (
const YAML::Node *pName = node.FindValue(MIN_INTENSITY))
116 min_intensity_node = pName;
118 if (min_intensity_node) {
119 float min_intensity_float;
120 *min_intensity_node >> min_intensity_float;
121 correction.second.min_intensity = floor(min_intensity_float);
124 correction.second.min_intensity = 0;
127 node[
FOCAL_SLOPE] >> correction.second.focal_slope;
130 correction.second.cos_rot_correction =
131 cosf(correction.second.rot_correction);
132 correction.second.sin_rot_correction =
133 sinf(correction.second.rot_correction);
134 correction.second.cos_vert_correction =
135 cosf(correction.second.vert_correction);
136 correction.second.sin_vert_correction =
137 sinf(correction.second.vert_correction);
139 correction.second.laser_ring = 0;
147 float distance_resolution_m;
149 const YAML::Node& lasers = node[
LASERS];
154 for (
int i = 0; i < num_lasers; i++) {
155 std::pair<int, LaserCorrection> correction;
156 lasers[i] >> correction;
157 const int index = correction.first;
170 double next_angle = -std::numeric_limits<double>::infinity();
171 for (
int ring = 0; ring < num_lasers; ++ring) {
174 double min_seen = std::numeric_limits<double>::infinity();
175 int next_index = num_lasers;
176 for (
int j = 0; j < num_lasers; ++j) {
179 if (next_angle < angle && angle < min_seen) {
185 if (next_index < num_lasers) {
189 next_angle = min_seen;
191 ROS_INFO(
"laser_ring[%2u] = %2u, angle = %+.6f",
192 next_index, ring, next_angle);
199 const std::pair<int, LaserCorrection> correction)
201 out << YAML::BeginMap;
202 out << YAML::Key << LASER_ID << YAML::Value << correction.first;
203 out << YAML::Key << ROT_CORRECTION <<
204 YAML::Value << correction.second.rot_correction;
205 out << YAML::Key << VERT_CORRECTION <<
206 YAML::Value << correction.second.vert_correction;
207 out << YAML::Key << DIST_CORRECTION <<
208 YAML::Value << correction.second.dist_correction;
209 out << YAML::Key << TWO_PT_CORRECTION_AVAILABLE <<
210 YAML::Value << correction.second.two_pt_correction_available;
211 out << YAML::Key << DIST_CORRECTION_X <<
212 YAML::Value << correction.second.dist_correction_x;
213 out << YAML::Key << DIST_CORRECTION_Y <<
214 YAML::Value << correction.second.dist_correction_y;
215 out << YAML::Key << VERT_OFFSET_CORRECTION <<
216 YAML::Value << correction.second.vert_offset_correction;
217 out << YAML::Key << HORIZ_OFFSET_CORRECTION <<
218 YAML::Value << correction.second.horiz_offset_correction;
219 out << YAML::Key << MAX_INTENSITY <<
220 YAML::Value << correction.second.max_intensity;
221 out << YAML::Key << MIN_INTENSITY <<
222 YAML::Value << correction.second.min_intensity;
223 out << YAML::Key << FOCAL_DISTANCE <<
224 YAML::Value << correction.second.focal_distance;
225 out << YAML::Key << FOCAL_SLOPE <<
226 YAML::Value << correction.second.focal_slope;
231 YAML::Emitter&
operator <<
234 out << YAML::BeginMap;
235 out << YAML::Key << NUM_LASERS <<
236 YAML::Value <<
calibration.laser_corrections.size();
237 out << YAML::Key << DISTANCE_RESOLUTION <<
239 out << YAML::Key << LASERS << YAML::Value << YAML::BeginSeq;
240 for (std::map<int, LaserCorrection>::const_iterator
242 it !=
calibration.laser_corrections_map.end(); it++)
251 void Calibration::read(
const std::string& calibration_file) {
252 std::ifstream fin(calibration_file.c_str());
253 if (!fin.is_open()) {
260 #ifdef HAVE_NEW_YAMLCPP 262 doc = YAML::LoadFile(calibration_file);
265 parser.GetNextDocument(doc);
268 }
catch (YAML::Exception &e) {
269 std::cerr <<
"YAML Exception: " << e.what() << std::endl;
275 void Calibration::write(
const std::string& calibration_file) {
276 std::ofstream fout(calibration_file.c_str());
const std::string ROT_CORRECTION
const std::string VERT_CORRECTION
const std::string MAX_INTENSITY
const std::string VERT_OFFSET_CORRECTION
YAML::Emitter & operator<<(YAML::Emitter &out, const Calibration &calibration)
void operator>>(const YAML::Node &node, Calibration &calibration)
const std::string DIST_CORRECTION_Y
const std::string DIST_CORRECTION
Calibration information for the entire device.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
std::vector< LaserCorrection > laser_corrections
const std::string DIST_CORRECTION_X
const std::string FOCAL_SLOPE
float distance_resolution_m
const std::string HORIZ_OFFSET_CORRECTION
std::map< int, LaserCorrection > laser_corrections_map
const std::string LASER_ID
const std::string DISTANCE_RESOLUTION
const std::string TWO_PT_CORRECTION_AVAILABLE
const std::string FOCAL_DISTANCE
const std::string MIN_INTENSITY
const std::string NUM_LASERS