Skip to content

Commit e4fa5fd

Browse files
committed
SCRIPT: wpiformat
1 parent 03bab7c commit e4fa5fd

File tree

745 files changed

+5415
-3879
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

745 files changed

+5415
-3879
lines changed

apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp

Lines changed: 18 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -22,13 +22,16 @@ AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) {
2222
throw std::runtime_error(fmt::format("Cannot open file: {}", path));
2323
}
2424

25-
wpi::util::json json = wpi::util::json::parse(fileBuffer.value()->GetCharBuffer());
25+
wpi::util::json json =
26+
wpi::util::json::parse(fileBuffer.value()->GetCharBuffer());
2627

2728
for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
2829
m_apriltags[tag.ID] = tag;
2930
}
30-
m_fieldWidth = wpi::units::meter_t{json.at("field").at("width").get<double>()};
31-
m_fieldLength = wpi::units::meter_t{json.at("field").at("length").get<double>()};
31+
m_fieldWidth =
32+
wpi::units::meter_t{json.at("field").at("width").get<double>()};
33+
m_fieldLength =
34+
wpi::units::meter_t{json.at("field").at("length").get<double>()};
3235
}
3336

3437
AprilTagFieldLayout::AprilTagFieldLayout(std::vector<AprilTag> apriltags,
@@ -64,8 +67,9 @@ void AprilTagFieldLayout::SetOrigin(OriginPosition origin) {
6467
SetOrigin(wpi::math::Pose3d{});
6568
break;
6669
case OriginPosition::kRedAllianceWallRightSide:
67-
SetOrigin(wpi::math::Pose3d{wpi::math::Translation3d{m_fieldLength, m_fieldWidth, 0_m},
68-
wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}});
70+
SetOrigin(wpi::math::Pose3d{
71+
wpi::math::Translation3d{m_fieldLength, m_fieldWidth, 0_m},
72+
wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}});
6973
break;
7074
default:
7175
throw std::invalid_argument("Invalid origin");
@@ -101,20 +105,22 @@ void AprilTagFieldLayout::Serialize(std::string_view path) {
101105
output.flush();
102106
}
103107

104-
void wpi::apriltag::to_json(wpi::util::json& json, const AprilTagFieldLayout& layout) {
108+
void wpi::apriltag::to_json(wpi::util::json& json,
109+
const AprilTagFieldLayout& layout) {
105110
std::vector<AprilTag> tagVector;
106111
tagVector.reserve(layout.m_apriltags.size());
107112
for (const auto& pair : layout.m_apriltags) {
108113
tagVector.push_back(pair.second);
109114
}
110115

111116
json = wpi::util::json{{"field",
112-
{{"length", layout.m_fieldLength.value()},
113-
{"width", layout.m_fieldWidth.value()}}},
114-
{"tags", tagVector}};
117+
{{"length", layout.m_fieldLength.value()},
118+
{"width", layout.m_fieldWidth.value()}}},
119+
{"tags", tagVector}};
115120
}
116121

117-
void wpi::apriltag::from_json(const wpi::util::json& json, AprilTagFieldLayout& layout) {
122+
void wpi::apriltag::from_json(const wpi::util::json& json,
123+
AprilTagFieldLayout& layout) {
118124
layout.m_apriltags.clear();
119125
for (const auto& tag : json.at("tags").get<std::vector<AprilTag>>()) {
120126
layout.m_apriltags[tag.ID] = tag;
@@ -164,6 +170,7 @@ AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) {
164170
return json.get<AprilTagFieldLayout>();
165171
}
166172

167-
AprilTagFieldLayout wpi::apriltag::LoadAprilTagLayoutField(AprilTagField field) {
173+
AprilTagFieldLayout wpi::apriltag::LoadAprilTagLayoutField(
174+
AprilTagField field) {
168175
return AprilTagFieldLayout::LoadField(field);
169176
}

apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,8 +47,8 @@ static wpi::math::Transform3d MakePose(const apriltag_pose_t& pose) {
4747
return {};
4848
}
4949
return {wpi::math::Translation3d{wpi::units::meter_t{pose.t->data[0]},
50-
wpi::units::meter_t{pose.t->data[1]},
51-
wpi::units::meter_t{pose.t->data[2]}},
50+
wpi::units::meter_t{pose.t->data[1]},
51+
wpi::units::meter_t{pose.t->data[2]}},
5252
wpi::math::Rotation3d{OrthogonalizeRotationMatrix(
5353
Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>>{
5454
pose.R->data})}};
@@ -130,8 +130,9 @@ AprilTagPoseEstimate AprilTagPoseEstimator::EstimateOrthogonalIteration(
130130
return rv;
131131
}
132132

133-
static wpi::math::Transform3d DoEstimate(const apriltag_detection_t* detection,
134-
const AprilTagPoseEstimator::Config& config) {
133+
static wpi::math::Transform3d DoEstimate(
134+
const apriltag_detection_t* detection,
135+
const AprilTagPoseEstimator::Config& config) {
135136
auto info = MakeDetectionInfo(detection, config);
136137
apriltag_pose_t pose;
137138
estimate_tag_pose(&info, &pose);

apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -517,7 +517,8 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseHomography
517517
return nullptr;
518518
}
519519

520-
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
520+
AprilTagPoseEstimator estimator(
521+
{wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
521522
return MakeJObject(env, estimator.EstimateHomography(harr));
522523
}
523524

@@ -553,7 +554,8 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseOrthogonalIteration
553554
return nullptr;
554555
}
555556

556-
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
557+
AprilTagPoseEstimator estimator(
558+
{wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
557559
return MakeJObject(env,
558560
estimator.EstimateOrthogonalIteration(harr, carr, nIters));
559561
}
@@ -590,7 +592,8 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePose
590592
return nullptr;
591593
}
592594

593-
AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
595+
AprilTagPoseEstimator estimator(
596+
{wpi::units::meter_t{tagSize}, fx, fy, cx, cy});
594597
return MakeJObject(env, estimator.Estimate(harr, carr));
595598
}
596599

apriltag/src/main/native/include/wpi/apriltag/AprilTagFieldLayout.hpp

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -24,10 +24,10 @@ namespace wpi::apriltag {
2424
*
2525
* The JSON format contains two top-level objects, "tags" and "field".
2626
* The "tags" object is a list of all AprilTags contained within a layout. Each
27-
* AprilTag serializes to a JSON object containing an ID and a wpi::math::Pose3d. The
28-
* "field" object is a descriptor of the size of the field in meters with
29-
* "width" and "length" values. This is to account for arbitrary field sizes
30-
* when transforming the poses.
27+
* AprilTag serializes to a JSON object containing an ID and a
28+
* wpi::math::Pose3d. The "field" object is a descriptor of the size of the
29+
* field in meters with "width" and "length" values. This is to account for
30+
* arbitrary field sizes when transforming the poses.
3131
*
3232
* Pose3ds in the JSON are measured using the normal FRC coordinate system, NWU
3333
* with the origin at the bottom-right corner of the blue alliance wall.
@@ -74,7 +74,8 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout {
7474
* @param fieldWidth Width of field the layout is representing.
7575
*/
7676
AprilTagFieldLayout(std::vector<AprilTag> apriltags,
77-
wpi::units::meter_t fieldLength, wpi::units::meter_t fieldWidth);
77+
wpi::units::meter_t fieldLength,
78+
wpi::units::meter_t fieldWidth);
7879

7980
/**
8081
* Returns the length of the field the layout is representing.

apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimator.hpp

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -66,15 +66,17 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
6666
* @param detection Tag detection
6767
* @return Pose estimate
6868
*/
69-
wpi::math::Transform3d EstimateHomography(const AprilTagDetection& detection) const;
69+
wpi::math::Transform3d EstimateHomography(
70+
const AprilTagDetection& detection) const;
7071

7172
/**
7273
* Estimates the pose of the tag using the homography method described in [1].
7374
*
7475
* @param homography Homography 3x3 matrix data
7576
* @return Pose estimate
7677
*/
77-
wpi::math::Transform3d EstimateHomography(std::span<const double, 9> homography) const;
78+
wpi::math::Transform3d EstimateHomography(
79+
std::span<const double, 9> homography) const;
7880

7981
/**
8082
* Estimates the pose of the tag. This returns one or two possible poses for
@@ -136,7 +138,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator {
136138
* @return Pose estimate
137139
*/
138140
wpi::math::Transform3d Estimate(std::span<const double, 9> homography,
139-
std::span<const double, 8> corners) const;
141+
std::span<const double, 8> corners) const;
140142

141143
private:
142144
Config m_config;

apriltag/src/test/native/cpp/AprilTagJsonTest.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,10 @@ using namespace wpi::apriltag;
1515

1616
TEST(AprilTagJsonTest, DeserializeMatches) {
1717
auto layout = AprilTagFieldLayout{
18-
std::vector{
19-
AprilTag{1, wpi::math::Pose3d{}},
20-
AprilTag{3, wpi::math::Pose3d{0_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}}},
18+
std::vector{AprilTag{1, wpi::math::Pose3d{}},
19+
AprilTag{3, wpi::math::Pose3d{0_m, 1_m, 0_m,
20+
wpi::math::Rotation3d{
21+
0_deg, 0_deg, 0_deg}}}},
2122
54_ft, 27_ft};
2223

2324
AprilTagFieldLayout deserialized;

apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -16,18 +16,21 @@ using namespace wpi::apriltag;
1616
TEST(AprilTagPoseSetOriginTest, TransformationMatches) {
1717
auto layout = AprilTagFieldLayout{
1818
std::vector<AprilTag>{
19-
AprilTag{1,
20-
wpi::math::Pose3d{0_ft, 0_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}},
2119
AprilTag{
22-
2, wpi::math::Pose3d{4_ft, 4_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}}},
20+
1, wpi::math::Pose3d{0_ft, 0_ft, 0_ft,
21+
wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}},
22+
AprilTag{2, wpi::math::Pose3d{4_ft, 4_ft, 4_ft,
23+
wpi::math::Rotation3d{0_deg, 0_deg,
24+
180_deg}}}},
2325
54_ft, 27_ft};
2426

2527
layout.SetOrigin(
2628
AprilTagFieldLayout::OriginPosition::kRedAllianceWallRightSide);
2729

28-
auto mirrorPose =
29-
wpi::math::Pose3d{54_ft, 27_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}};
30+
auto mirrorPose = wpi::math::Pose3d{
31+
54_ft, 27_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}};
3032
EXPECT_EQ(mirrorPose, *layout.GetTagPose(1));
31-
mirrorPose = wpi::math::Pose3d{50_ft, 23_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
33+
mirrorPose = wpi::math::Pose3d{50_ft, 23_ft, 4_ft,
34+
wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
3235
EXPECT_EQ(mirrorPose, *layout.GetTagPose(2));
3336
}

apriltag/src/test/native/cpp/LoadConfigTest.cpp

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -27,20 +27,23 @@ TEST(AprilTagFieldsTest, TestLoad2022RapidReact) {
2727

2828
// Blue Hangar Truss - Hub
2929
auto expectedPose =
30-
wpi::math::Pose3d{127.272_in, 216.01_in, 67.932_in, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
30+
wpi::math::Pose3d{127.272_in, 216.01_in, 67.932_in,
31+
wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}};
3132
auto maybePose = layout.GetTagPose(1);
3233
EXPECT_TRUE(maybePose);
3334
EXPECT_EQ(expectedPose, *maybePose);
3435

3536
// Blue Terminal Near Station
36-
expectedPose = wpi::math::Pose3d{4.768_in, 67.631_in, 35.063_in,
37+
expectedPose =
38+
wpi::math::Pose3d{4.768_in, 67.631_in, 35.063_in,
3739
wpi::math::Rotation3d{0_deg, 0_deg, 46.25_deg}};
3840
maybePose = layout.GetTagPose(5);
3941
EXPECT_TRUE(maybePose);
4042
EXPECT_EQ(expectedPose, *maybePose);
4143

4244
// Upper Hub Blue-Near
43-
expectedPose = wpi::math::Pose3d{332.321_in, 183.676_in, 95.186_in,
45+
expectedPose =
46+
wpi::math::Pose3d{332.321_in, 183.676_in, 95.186_in,
4447
wpi::math::Rotation3d{0_deg, 26.75_deg, 69_deg}};
4548
maybePose = layout.GetTagPose(53);
4649
EXPECT_TRUE(maybePose);

cameraserver/multiCameraServer/src/main/native/cpp/main.cpp

Lines changed: 18 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -72,18 +72,19 @@ bool ReadCameraConfig(const wpi::util::json& config) {
7272
try {
7373
c.name = config.at("name").get<std::string>();
7474
} catch (const wpi::util::json::exception& e) {
75-
wpi::util::print(stderr, "config error in '{}': could not read camera name: {}\n",
76-
configFile, e.what());
75+
wpi::util::print(stderr,
76+
"config error in '{}': could not read camera name: {}\n",
77+
configFile, e.what());
7778
return false;
7879
}
7980

8081
// path
8182
try {
8283
c.path = config.at("path").get<std::string>();
8384
} catch (const wpi::util::json::exception& e) {
84-
wpi::util::print(stderr,
85-
"config error in '{}': camera '{}': could not read path: {}\n",
86-
configFile, c.name, e.what());
85+
wpi::util::print(
86+
stderr, "config error in '{}': camera '{}': could not read path: {}\n",
87+
configFile, c.name, e.what());
8788
return false;
8889
}
8990

@@ -98,7 +99,7 @@ bool ReadConfig() {
9899
auto fileBuffer = wpi::util::MemoryBuffer::GetFile(configFile);
99100
if (!fileBuffer) {
100101
wpi::util::print(stderr, "could not open '{}': {}\n", configFile,
101-
fileBuffer.error().message());
102+
fileBuffer.error().message());
102103
return false;
103104
}
104105

@@ -108,23 +109,24 @@ bool ReadConfig() {
108109
j = wpi::util::json::parse(fileBuffer.value()->GetCharBuffer());
109110
} catch (const wpi::util::json::parse_error& e) {
110111
wpi::util::print(stderr, "config error in '{}': byte {}: {}\n", configFile,
111-
e.byte, e.what());
112+
e.byte, e.what());
112113
return false;
113114
}
114115

115116
// top level must be an object
116117
if (!j.is_object()) {
117118
wpi::util::print(stderr, "config error in '{}': must be JSON object\n",
118-
configFile);
119+
configFile);
119120
return false;
120121
}
121122

122123
// team number
123124
try {
124125
team = j.at("team").get<unsigned int>();
125126
} catch (const wpi::util::json::exception& e) {
126-
wpi::util::print(stderr, "config error in '{}': could not read team number: {}\n",
127-
configFile, e.what());
127+
wpi::util::print(stderr,
128+
"config error in '{}': could not read team number: {}\n",
129+
configFile, e.what());
128130
return false;
129131
}
130132

@@ -143,8 +145,9 @@ bool ReadConfig() {
143145
configFile, str);
144146
}
145147
} catch (const wpi::util::json::exception& e) {
146-
wpi::util::print(stderr, "config error in '{}': could not read ntmode: {}\n",
147-
configFile, e.what());
148+
wpi::util::print(stderr,
149+
"config error in '{}': could not read ntmode: {}\n",
150+
configFile, e.what());
148151
}
149152
}
150153

@@ -156,8 +159,9 @@ bool ReadConfig() {
156159
}
157160
}
158161
} catch (const wpi::util::json::exception& e) {
159-
wpi::util::print(stderr, "config error in '{}': could not read cameras: {}\n",
160-
configFile, e.what());
162+
wpi::util::print(stderr,
163+
"config error in '{}': could not read cameras: {}\n",
164+
configFile, e.what());
161165
return false;
162166
}
163167

command2/src/main/native/cpp/frc2/command/CommandPtr.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,9 @@ CommandPtr::CommandPtr(CommandPtr&& rhs) {
3838

3939
void CommandPtr::AssertValid() const {
4040
if (!m_ptr) {
41-
throw WPILIB_MakeError(wpi::err::CommandIllegalUse,
42-
"Moved-from CommandPtr object used!\nMoved out at:\n{}",
43-
m_moveOutSite);
41+
throw WPILIB_MakeError(
42+
wpi::err::CommandIllegalUse,
43+
"Moved-from CommandPtr object used!\nMoved out at:\n{}", m_moveOutSite);
4444
}
4545
}
4646

0 commit comments

Comments
 (0)