Format constants file better
Update constants_formatting to match google style guide, and output
clang-formatted output.
Change-Id: Ic04798c85193cab525e243be5a934d6217937517
diff --git a/y2019/vision/constants.cc b/y2019/vision/constants.cc
index fa7c130..bc8a56d 100644
--- a/y2019/vision/constants.cc
+++ b/y2019/vision/constants.cc
@@ -7,85 +7,108 @@
CameraCalibration camera_4 = {
{
- 3.73623 / 180.0 * M_PI, 588.1, 0.269291 / 180.0 * M_PI,
+ 3.73623 / 180.0 * M_PI, 588.1, 0.269291 / 180.0 * M_PI,
},
{
- {{6.02674 * kInchesToMeters, 4.57805 * kInchesToMeters,
- 33.3849 * kInchesToMeters}},
- 22.4535 / 180.0 * M_PI,
+ {{6.02674 * kInchesToMeters, 4.57805 * kInchesToMeters,
+ 33.3849 * kInchesToMeters}},
+ 22.4535 / 180.0 * M_PI,
},
{
- 4,
- {{12.5 * kInchesToMeters, 12 * kInchesToMeters}},
- {{1 * kInchesToMeters, 0.0}},
- 26,
- "cam4_0/debug_viewer_jpeg_",
- 52,
+ 4,
+ {{12.5 * kInchesToMeters, 12 * kInchesToMeters}},
+ {{1 * kInchesToMeters, 0.0}},
+ 26,
+ "cam4_0/debug_viewer_jpeg_",
+ 52,
}};
CameraCalibration camera_5 = {
{
- 1.00774 / 180.0 * M_PI, 658.554, 2.43864 / 180.0 * M_PI,
+ 1.00774 / 180.0 * M_PI, 658.554, 2.43864 / 180.0 * M_PI,
},
{
- {{5.51248 * kInchesToMeters, 2.04087 * kInchesToMeters,
- 33.2555 * kInchesToMeters}},
- -13.1396 / 180.0 * M_PI,
+ {{5.51248 * kInchesToMeters, 2.04087 * kInchesToMeters,
+ 33.2555 * kInchesToMeters}},
+ -13.1396 / 180.0 * M_PI,
},
{
- 5,
- {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
- {{1 * kInchesToMeters, 0.0}},
- 26,
- "cam5_0/debug_viewer_jpeg_",
- 59,
+ 5,
+ {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
+ {{1 * kInchesToMeters, 0.0}},
+ 26,
+ "cam5_0/debug_viewer_jpeg_",
+ 59,
+ }};
+
+CameraCalibration camera_10 = {
+ {
+ 0.0429164 / 180.0 * M_PI, 337.247, 0.865625 / 180.0 * M_PI,
+ },
+ {
+ {{20.5486 * kInchesToMeters, -2.47638 * kInchesToMeters,
+ 33.1395 * kInchesToMeters}},
+ 2.08049 / 180.0 * M_PI,
+ },
+ {
+ 10,
+ {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
+ {{1 * kInchesToMeters, 0.0}},
+ 26,
+ "data/cam10_0/debug_viewer_jpeg_",
+ 59,
}};
CameraCalibration camera_16 = {
{
- -1.30906 / 180.0 * M_PI, 347.372, 2.18486 / 180.0 * M_PI,
+ -1.30906 / 180.0 * M_PI, 347.372, 2.18486 / 180.0 * M_PI,
},
{
- {{4.98126 * kInchesToMeters, 1.96988 * kInchesToMeters,
- 33.4276 * kInchesToMeters}},
- -12.2377 / 180.0 * M_PI,
+ {{4.98126 * kInchesToMeters, 1.96988 * kInchesToMeters,
+ 33.4276 * kInchesToMeters}},
+ -12.2377 / 180.0 * M_PI,
},
{
- 16,
- {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
- {{1 * kInchesToMeters, 0.0}},
- 16,
- "cam16/debug_viewer_jpeg_",
- 55,
+ 16,
+ {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
+ {{1 * kInchesToMeters, 0.0}},
+ 16,
+ "cam16/debug_viewer_jpeg_",
+ 55,
}};
-// Note: x/y should be negated and heading should be offset by 180 deg to
-// account for this being calibrated on the rear of the robot.
CameraCalibration camera_19 = {
{
- -0.341036 / 180.0 * M_PI, 324.626, 1.2545 / 180.0 * M_PI,
+ -0.341036 / 180.0 * M_PI, 324.626, 1.2545 / 180.0 * M_PI,
},
{
- {{6.93309 * kInchesToMeters, -2.64735 * kInchesToMeters,
- 32.8758 * kInchesToMeters}},
- 2.58102 / 180.0 * M_PI,
+ {{6.93309 * kInchesToMeters, -2.64735 * kInchesToMeters,
+ 32.8758 * kInchesToMeters}},
+ 2.58102 / 180.0 * M_PI,
},
{
- 19,
- {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
- {{1 * kInchesToMeters, 0.0}},
- 16,
- "cam19/debug_viewer_jpeg_",
- 68,
+ 19,
+ {{12.5 * kInchesToMeters, 0.5 * kInchesToMeters}},
+ {{1 * kInchesToMeters, 0.0}},
+ 16,
+ "cam19/debug_viewer_jpeg_",
+ 68,
}};
const CameraCalibration *GetCamera(int camera_id) {
switch (camera_id) {
- case 4: return &camera_4;
- case 5: return &camera_5;
- case 16: return &camera_16;
- case 19: return &camera_19;
- default: return nullptr;
+ case 4:
+ return &camera_4;
+ case 5:
+ return &camera_5;
+ case 10:
+ return &camera_10;
+ case 16:
+ return &camera_16;
+ case 19:
+ return &camera_19;
+ default:
+ return nullptr;
}
}
diff --git a/y2019/vision/constants.h b/y2019/vision/constants.h
index b33b045..cc6775e 100644
--- a/y2019/vision/constants.h
+++ b/y2019/vision/constants.h
@@ -30,7 +30,7 @@
return out;
}
- void dump(std::basic_ostream<char> &o) const;
+ void Dump(std::basic_ostream<char> *o) const;
};
struct IntrinsicParams {
@@ -53,7 +53,7 @@
out.barrel_mount = data[2];
return out;
}
- void dump(std::basic_ostream<char> &o) const;
+ void Dump(std::basic_ostream<char> *o) const;
};
// Metadata about the calibration results (Should be good enough to reproduce).
@@ -68,7 +68,7 @@
const char *filename_prefix;
int num_images;
- void dump(std::basic_ostream<char> &o) const;
+ void Dump(std::basic_ostream<char> *o) const;
};
struct CameraCalibration {
diff --git a/y2019/vision/constants_formatting.cc b/y2019/vision/constants_formatting.cc
index 74a9ed3..272246e 100644
--- a/y2019/vision/constants_formatting.cc
+++ b/y2019/vision/constants_formatting.cc
@@ -30,26 +30,25 @@
return ss.str();
}
-void IntrinsicParams::dump(std::basic_ostream<char> &o) const {
- o << " {\n " << fmt_rad(mount_angle) << ", " << focal_length;
- o << ", " << fmt_rad(barrel_mount) << ",\n },\n";
+void IntrinsicParams::Dump(std::basic_ostream<char> *o) const {
+ *o << " {\n " << fmt_rad(mount_angle) << ", " << focal_length;
+ *o << ", " << fmt_rad(barrel_mount) << ",\n },\n";
}
-void CameraGeometry::dump(std::basic_ostream<char> &o) const {
- o << "{{{" << fmt_meters(location[0]) << ", " << fmt_meters(location[1])
- << ", " << fmt_meters(location[2]) << "}}," << fmt_rad(heading) << ",},";
+void CameraGeometry::Dump(std::basic_ostream<char> *o) const {
+ *o << " {\n {{" << fmt_meters(location[0]) << ", "
+ << fmt_meters(location[1]) << ",\n " << fmt_meters(location[2])
+ << "}},\n " << fmt_rad(heading) << ",\n },\n ";
}
-void DatasetInfo::dump(std::basic_ostream<char> &o) const {
- o << "{\n"
- << camera_id << ", "
- << "{{" << fmt_meters(to_tape_measure_start[0]) << ", "
- << fmt_meters(to_tape_measure_start[1]) << "}},\n"
- << "{{" << fmt_meters(tape_measure_direction[0]) << ", "
- << fmt_meters(tape_measure_direction[1]) << "}},\n"
- << beginning_tape_measure_reading << ",\n"
- << "\"" << filename_prefix << "\",\n"
- << num_images << ",\n}";
+void DatasetInfo::Dump(std::basic_ostream<char> *o) const {
+ *o << "{\n " << camera_id << ",\n "
+ << "{{" << fmt_meters(to_tape_measure_start[0]) << ", "
+ << fmt_meters(to_tape_measure_start[1]) << "}},\n "
+ << "{{" << fmt_meters(tape_measure_direction[0]) << ", "
+ << fmt_meters(tape_measure_direction[1]) << "}},\n "
+ << beginning_tape_measure_reading << ",\n "
+ << "\"" << filename_prefix << "\",\n " << num_images << ",\n }";
}
void DumpCameraConstants(int camera_id, const CameraCalibration &value) {
@@ -68,9 +67,9 @@
auto *params = (i == camera_id) ? &value : GetCamera(i);
if (params) {
o << "\nCameraCalibration camera_" << i << " = {\n";
- params->intrinsics.dump(o);
- params->geometry.dump(o);
- params->dataset.dump(o);
+ params->intrinsics.Dump(&o);
+ params->geometry.Dump(&o);
+ params->dataset.Dump(&o);
o << "};\n";
}
}
@@ -81,10 +80,11 @@
)";
for (int i = 0; i < kMaxNumCameras; ++i) {
if (i == camera_id || GetCamera(i) != nullptr) {
- o << " case " << i << ": return &camera_" << i << ";\n";
+ o << " case " << i << ":\n return &camera_" << i << ";\n";
}
}
- o << R"( default: return nullptr;
+ o << R"( default:
+ return nullptr;
}
}