Nest all namespaces
The compiler supports this now. We can type less going forward.
No functional changes.
Signed-off-by: Stephan Pleines <pleines.stephan@gmail.com>
Change-Id: I29d6fa4f9aacc0e381f1a7637294db0392466995
diff --git a/frc971/control_loops/binomial.h b/frc971/control_loops/binomial.h
index 4f4c4dc..9ccc824 100644
--- a/frc971/control_loops/binomial.h
+++ b/frc971/control_loops/binomial.h
@@ -1,8 +1,7 @@
#ifndef FRC971_CONTROL_LOOPS_BINOMIAL_H_
#define FRC971_CONTROL_LOOPS_BINOMIAL_H_
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Computes the factorial of n
constexpr double Factorial(int n) {
@@ -18,7 +17,6 @@
return Factorial(n) / (Factorial(k) * Factorial(n - k));
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_BINOMIAL_H_
diff --git a/frc971/control_loops/binomial_test.cc b/frc971/control_loops/binomial_test.cc
index 482790e..dc25e23 100644
--- a/frc971/control_loops/binomial_test.cc
+++ b/frc971/control_loops/binomial_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// Tests some factorials.
TEST(BinomialTest, Factorial) {
@@ -39,6 +37,4 @@
EXPECT_EQ(1.0, Binomial(4, 4));
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/c2d_test.cc b/frc971/control_loops/c2d_test.cc
index 14b4952..47a87a0 100644
--- a/frc971/control_loops/c2d_test.cc
+++ b/frc971/control_loops/c2d_test.cc
@@ -6,9 +6,7 @@
#include "frc971/control_loops/runge_kutta.h"
-namespace frc971 {
-namespace controls {
-namespace testing {
+namespace frc971::controls::testing {
class C2DTest : public ::testing::Test {
public:
@@ -86,6 +84,4 @@
EXPECT_LT((A_d - A_d_fast).norm(), 1e-20);
}
-} // namespace testing
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls::testing
diff --git a/frc971/control_loops/coerce_goal.cc b/frc971/control_loops/coerce_goal.cc
index ccad84a..4a7f3ed 100644
--- a/frc971/control_loops/coerce_goal.cc
+++ b/frc971/control_loops/coerce_goal.cc
@@ -3,7 +3,3 @@
#include "Eigen/Dense"
#include "frc971/control_loops/polytope.h"
-
-namespace frc971 {
-namespace control_loops {} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/coerce_goal_test.cc b/frc971/control_loops/coerce_goal_test.cc
index 95520db..dc69b70 100644
--- a/frc971/control_loops/coerce_goal_test.cc
+++ b/frc971/control_loops/coerce_goal_test.cc
@@ -6,8 +6,7 @@
#include "frc971/control_loops/polytope.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
namespace {
@@ -213,5 +212,4 @@
EXPECT_EQ(result(1, 0), 0);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/control_loop.cc b/frc971/control_loops/control_loop.cc
index 3b475a9..63fe703 100644
--- a/frc971/control_loops/control_loop.cc
+++ b/frc971/control_loops/control_loop.cc
@@ -1,5 +1 @@
#include "frc971/control_loops/control_loop.h"
-
-namespace frc971 {
-namespace controls {} // namespace controls
-} // namespace frc971
diff --git a/frc971/control_loops/control_loop_test.cc b/frc971/control_loops/control_loop_test.cc
index 6704bf5..28e3504 100644
--- a/frc971/control_loops/control_loop_test.cc
+++ b/frc971/control_loops/control_loop_test.cc
@@ -1,7 +1,3 @@
#include "frc971/control_loops/control_loop_test.h"
#include <chrono>
-
-namespace frc971 {
-namespace testing {} // namespace testing
-} // namespace frc971
diff --git a/frc971/control_loops/double_jointed_arm/demo_path.cc b/frc971/control_loops/double_jointed_arm/demo_path.cc
index 8d549d1..5b52bf3 100644
--- a/frc971/control_loops/double_jointed_arm/demo_path.cc
+++ b/frc971/control_loops/double_jointed_arm/demo_path.cc
@@ -4,9 +4,7 @@
#include <initializer_list>
#include <memory>
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
::std::vector<::std::array<double, 6>> FlipPath(
::std::initializer_list<::std::array<double, 6>> list) {
@@ -210,6 +208,4 @@
return ::std::unique_ptr<Path>(new Path(Path::Reversed(*MakeDemoPath())));
}
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.cc b/frc971/control_loops/double_jointed_arm/dynamics.cc
index 2842ad4..4910e6c 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics.cc
+++ b/frc971/control_loops/double_jointed_arm/dynamics.cc
@@ -2,9 +2,7 @@
DEFINE_bool(gravity, true, "If true, enable gravity.");
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
Dynamics::Dynamics(ArmConstants arm_constants)
: arm_constants_(arm_constants),
@@ -32,6 +30,4 @@
beta_(arm_constants_.l0 * arm_constants_.r1 * arm_constants_.m1),
gamma_(arm_constants_.j1 +
arm_constants_.r1 * arm_constants_.r1 * arm_constants_.m1) {}
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
diff --git a/frc971/control_loops/double_jointed_arm/dynamics_test.cc b/frc971/control_loops/double_jointed_arm/dynamics_test.cc
index 5234af5..9f68ddc 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics_test.cc
+++ b/frc971/control_loops/double_jointed_arm/dynamics_test.cc
@@ -4,10 +4,7 @@
#include "frc971/control_loops/double_jointed_arm/test_constants.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
-namespace testing {
+namespace frc971::control_loops::arm::testing {
// Tests that zero inputs result in no acceleration and no motion.
// This isn't all that rigerous, but it's a good start.
@@ -48,7 +45,4 @@
.isApprox(X));
}
-} // namespace testing
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm::testing
diff --git a/frc971/control_loops/double_jointed_arm/ekf.cc b/frc971/control_loops/double_jointed_arm/ekf.cc
index f8ec6d6..b1ae70a 100644
--- a/frc971/control_loops/double_jointed_arm/ekf.cc
+++ b/frc971/control_loops/double_jointed_arm/ekf.cc
@@ -12,9 +12,7 @@
DEFINE_double(distal_voltage_error_uncertainty, 2.0,
"Distal joint voltage error uncertainty.");
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
namespace {
// TODO(austin): When tuning this, make sure to verify that you are waiting
@@ -108,6 +106,4 @@
P_;
}
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
diff --git a/frc971/control_loops/double_jointed_arm/graph.cc b/frc971/control_loops/double_jointed_arm/graph.cc
index b5a70ab..a60a000 100644
--- a/frc971/control_loops/double_jointed_arm/graph.cc
+++ b/frc971/control_loops/double_jointed_arm/graph.cc
@@ -3,9 +3,7 @@
#include <algorithm>
#include <cassert>
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
SearchGraph::SearchGraph(size_t num_vertexes, std::initializer_list<Edge> edges)
: SearchGraph(num_vertexes, ::std::vector<Edge>(edges)) {}
@@ -66,6 +64,4 @@
return vertexes_[vertex].cached_distance;
}
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
diff --git a/frc971/control_loops/double_jointed_arm/graph_test.cc b/frc971/control_loops/double_jointed_arm/graph_test.cc
index 7b14ced..771d1a0 100644
--- a/frc971/control_loops/double_jointed_arm/graph_test.cc
+++ b/frc971/control_loops/double_jointed_arm/graph_test.cc
@@ -2,10 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
-namespace testing {
+namespace frc971::control_loops::arm::testing {
class HeapTest {
public:
@@ -65,7 +62,4 @@
}
}
-} // namespace testing
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm::testing
diff --git a/frc971/control_loops/double_jointed_arm/trajectory.cc b/frc971/control_loops/double_jointed_arm/trajectory.cc
index 05a2d17..8b5129d 100644
--- a/frc971/control_loops/double_jointed_arm/trajectory.cc
+++ b/frc971/control_loops/double_jointed_arm/trajectory.cc
@@ -13,9 +13,7 @@
DEFINE_double(lqr_distal_pos, 0.20, "Position LQR gain");
DEFINE_double(lqr_distal_vel, 4.0, "Velocity LQR gain");
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
Path Path::Reversed(const Path &p) {
::std::vector<::std::array<double, 6>> list(p.distances().size());
@@ -621,6 +619,4 @@
omega_ = trajectory_->OmegaT(goal_(0), goal_(1));
}
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
diff --git a/frc971/control_loops/double_jointed_arm/trajectory_test.cc b/frc971/control_loops/double_jointed_arm/trajectory_test.cc
index 99575e9..88962f9 100644
--- a/frc971/control_loops/double_jointed_arm/trajectory_test.cc
+++ b/frc971/control_loops/double_jointed_arm/trajectory_test.cc
@@ -7,10 +7,7 @@
#include "frc971/control_loops/double_jointed_arm/ekf.h"
#include "frc971/control_loops/double_jointed_arm/test_constants.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
-namespace testing {
+namespace frc971::control_loops::arm::testing {
// Tests that we can pull out values along the path.
TEST(TrajectoryTest, Theta) {
@@ -210,7 +207,4 @@
final_theta_t.isApprox(trajectory.path().Theta(follower.goal(0))));
}
-} // namespace testing
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm::testing
diff --git a/frc971/control_loops/drivetrain/camera_test.cc b/frc971/control_loops/drivetrain/camera_test.cc
index a55ebad..baf2995 100644
--- a/frc971/control_loops/drivetrain/camera_test.cc
+++ b/frc971/control_loops/drivetrain/camera_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// Check that a Target's basic operations work.
TEST(TargetTest, BasicTargetTest) {
@@ -208,6 +206,4 @@
Reading({0.0, 1.0, 0.0, ::std::numeric_limits<double>::infinity()}),
Reading({0.0, 1.0, 0.0, ::std::numeric_limits<double>::quiet_NaN()})));
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/drivetrain/distance_spline.cc b/frc971/control_loops/drivetrain/distance_spline.cc
index 04a1add..bcd9d4c 100644
--- a/frc971/control_loops/drivetrain/distance_spline.cc
+++ b/frc971/control_loops/drivetrain/distance_spline.cc
@@ -5,9 +5,7 @@
#include "aos/logging/logging.h"
#include "frc971/control_loops/drivetrain/spline.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
::std::vector<float> DistanceSpline::BuildDistances(size_t num_alpha) {
num_alpha = num_alpha == 0 ? 100 * splines().size() : num_alpha;
@@ -233,6 +231,4 @@
return {index, alpha - index};
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/distance_spline_test.cc b/frc971/control_loops/drivetrain/distance_spline_test.cc
index 60f83b9..806d39e 100644
--- a/frc971/control_loops/drivetrain/distance_spline_test.cc
+++ b/frc971/control_loops/drivetrain/distance_spline_test.cc
@@ -13,10 +13,7 @@
DEFINE_bool(plot, false, "If true, plot");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
// Test fixture with a spline from 0, 0 to 1, 1
class ParameterizedDistanceSplineTest
@@ -187,7 +184,4 @@
1.5, 2.0, 1.0, 1.0, 0.0, 0.0)
.finished()))})));
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index be4cf6f..cdccd7d 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -24,9 +24,7 @@
using ::aos::monotonic_clock;
namespace chrono = ::std::chrono;
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace {
// Maximum variation to allow in the gyro when zeroing.
@@ -627,6 +625,4 @@
return builder.Finish();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
index 3e17822..3cce7d2 100644
--- a/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_lib_test.cc
@@ -27,10 +27,7 @@
DEFINE_string(output_file, "",
"If set, logs all channels to the provided logfile.");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
namespace chrono = ::std::chrono;
using ::aos::monotonic_clock;
@@ -1639,7 +1636,4 @@
// TODO(austin): Make sure the profile reset code when we disable works.
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/drivetrain_states.h b/frc971/control_loops/drivetrain/drivetrain_states.h
index 9ea2518..70ad69d 100644
--- a/frc971/control_loops/drivetrain/drivetrain_states.h
+++ b/frc971/control_loops/drivetrain/drivetrain_states.h
@@ -1,9 +1,7 @@
#ifndef FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_STATES_H_
#define FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_STATES_H_
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops ::drivetrain {
enum KalmanState {
kLeftPosition = 0,
@@ -17,8 +15,6 @@
enum OutputState { kLeftVoltage = 0, kRightVoltage = 1 };
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_STATES_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
index ab7e280..c8e4dee 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.cc
@@ -20,10 +20,7 @@
DEFINE_bool(plot, false, "If true, plot");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
namespace {
// TODO(Comran): Make one that doesn't depend on the actual values for a
@@ -383,7 +380,4 @@
#endif
}
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/drivetrain_uc.q.cc b/frc971/control_loops/drivetrain/drivetrain_uc.q.cc
index 2a2870c..bc71e4e 100644
--- a/frc971/control_loops/drivetrain/drivetrain_uc.q.cc
+++ b/frc971/control_loops/drivetrain/drivetrain_uc.q.cc
@@ -2,8 +2,7 @@
#include <cinttypes>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
GearLogging::GearLogging() { Zero(); }
@@ -104,5 +103,4 @@
DrivetrainQueue_Status::DrivetrainQueue_Status() { Zero(); }
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/drivetrain/gear.h b/frc971/control_loops/drivetrain/gear.h
index 8fabb69..ff43e20 100644
--- a/frc971/control_loops/drivetrain/gear.h
+++ b/frc971/control_loops/drivetrain/gear.h
@@ -1,10 +1,7 @@
#ifndef FRC971_CONTROL_LOOPS_GEAR_H_
#define FRC971_CONTROL_LOOPS_GEAR_H_
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-
+namespace frc971::control_loops::drivetrain {
// The state of the shift.
enum class Gear { HIGH, LOW, SHIFTING_UP, SHIFTING_DOWN };
@@ -18,8 +15,6 @@
return gear == Gear::LOW || gear == Gear::HIGH;
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_GEAR_H_
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
index 01028c0..2119c7d 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
+++ b/frc971/control_loops/drivetrain/hybrid_ekf_test.cc
@@ -9,10 +9,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
typedef HybridEkf<>::StateIdx StateIdx;
typedef HybridEkf<>::InputIdx InputIdx;
@@ -503,7 +500,4 @@
"make_h");
}
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator.cc b/frc971/control_loops/drivetrain/improved_down_estimator.cc
index 71347e2..b7b3878 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator.cc
+++ b/frc971/control_loops/drivetrain/improved_down_estimator.cc
@@ -5,9 +5,7 @@
#include "frc971/control_loops/quaternion_utils.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
void QuaternionUkf::Reset() {
// The various noise matrices are tuned to provide values that seem
@@ -319,6 +317,4 @@
return builder.Finish();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
index 376c131..c128429 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
+++ b/frc971/control_loops/drivetrain/improved_down_estimator_test.cc
@@ -11,9 +11,7 @@
#include "frc971/control_loops/quaternion_utils.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
namespace {
// Check if two quaternions are logically equal, to within some reasonable
@@ -221,6 +219,4 @@
"covariance.";
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/drivetrain/libspline.cc b/frc971/control_loops/drivetrain/libspline.cc
index f275c17..57abe69 100644
--- a/frc971/control_loops/drivetrain/libspline.cc
+++ b/frc971/control_loops/drivetrain/libspline.cc
@@ -10,9 +10,7 @@
#include "frc971/control_loops/drivetrain/trajectory.h"
#include "y2020/control_loops/drivetrain/drivetrain_base.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
extern "C" {
// Based on spline.h
@@ -204,6 +202,4 @@
void SetUpLogging() { ::aos::network::OverrideTeamNumber(971); }
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
index 355710c..e54376c 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.cc
@@ -8,9 +8,7 @@
#include "frc971/control_loops/c2d.h"
#include "frc971/control_loops/dlqr.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace {
namespace chrono = ::std::chrono;
} // namespace
@@ -308,6 +306,4 @@
return line_follow_logging_builder.Finish();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
index d2ebb4e..ed018b9 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain_test.cc
@@ -14,10 +14,7 @@
namespace chrono = ::std::chrono;
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
class LineFollowDrivetrainTest : public ::testing::Test {
public:
@@ -395,7 +392,4 @@
0.125 * state.x() * state.x();
})));
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer.cc b/frc971/control_loops/drivetrain/localization/puppet_localizer.cc
index 8a60ea5..9215702 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer.cc
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer.cc
@@ -1,8 +1,6 @@
#include "frc971/control_loops/drivetrain/localization/puppet_localizer.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
PuppetLocalizer::PuppetLocalizer(
aos::EventLoop *event_loop,
@@ -98,6 +96,4 @@
}
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
index 1a71d5a..a4338a8 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer_test.cc
@@ -18,10 +18,7 @@
DEFINE_string(output_folder, "",
"If set, logs all channels to the provided logfile.");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
using frc971::control_loops::drivetrain::DrivetrainConfig;
using frc971::control_loops::drivetrain::Goal;
@@ -207,7 +204,4 @@
EXPECT_TRUE(VerifyEstimatorAccurate(5e-3));
}
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.cc b/frc971/control_loops/drivetrain/polydrivetrain.cc
index b52b67f..c20e4ab 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.cc
+++ b/frc971/control_loops/drivetrain/polydrivetrain.cc
@@ -1,7 +1 @@
#include "frc971/control_loops/drivetrain/polydrivetrain.h"
-
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
diff --git a/frc971/control_loops/drivetrain/spline.cc b/frc971/control_loops/drivetrain/spline.cc
index 609d3b1..a7f749e 100644
--- a/frc971/control_loops/drivetrain/spline.cc
+++ b/frc971/control_loops/drivetrain/spline.cc
@@ -1,8 +1,6 @@
#include "frc971/control_loops/drivetrain/spline.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
::Eigen::Matrix<double, 2, 6> Spline4To6(
const ::Eigen::Matrix<double, 2, 4> &control_points) {
@@ -36,6 +34,4 @@
return new_control_points;
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/spline_test.cc b/frc971/control_loops/drivetrain/spline_test.cc
index 6498fb6..6d84d53 100644
--- a/frc971/control_loops/drivetrain/spline_test.cc
+++ b/frc971/control_loops/drivetrain/spline_test.cc
@@ -9,10 +9,7 @@
DEFINE_bool(plot, false, "If true, plot");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
std::string TestName() {
const ::testing::TestInfo *info =
@@ -258,7 +255,4 @@
}
}
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.cc b/frc971/control_loops/drivetrain/splinedrivetrain.cc
index 977529f..508967c 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.cc
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.cc
@@ -11,9 +11,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
SplineDrivetrain::SplineDrivetrain(const DrivetrainConfig<double> &dt_config)
: dt_config_(dt_config),
@@ -268,6 +266,4 @@
return MakeTrajectoryLogging(builder->fbb());
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/ssdrivetrain.cc b/frc971/control_loops/drivetrain/ssdrivetrain.cc
index e1c4dac..74cc6ff 100644
--- a/frc971/control_loops/drivetrain/ssdrivetrain.cc
+++ b/frc971/control_loops/drivetrain/ssdrivetrain.cc
@@ -9,9 +9,7 @@
#include "frc971/control_loops/polytope.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
DrivetrainMotorsSS::DrivetrainMotorsSS(
const DrivetrainConfig<double> &dt_config, StateFeedbackLoop<7, 2, 4> *kf,
@@ -300,6 +298,4 @@
profiled_gyro_left_right(kRightVelocity));
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/trajectory.cc b/frc971/control_loops/drivetrain/trajectory.cc
index 76a6784..36d0947 100644
--- a/frc971/control_loops/drivetrain/trajectory.cc
+++ b/frc971/control_loops/drivetrain/trajectory.cc
@@ -12,9 +12,7 @@
#include "frc971/control_loops/hybrid_state_feedback_loop.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace {
float DefaultConstraint(ConstraintType type) {
@@ -906,6 +904,4 @@
return result;
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/trajectory_generator.cc b/frc971/control_loops/drivetrain/trajectory_generator.cc
index d022b34..8e3e0f8 100644
--- a/frc971/control_loops/drivetrain/trajectory_generator.cc
+++ b/frc971/control_loops/drivetrain/trajectory_generator.cc
@@ -1,8 +1,6 @@
#include "frc971/control_loops/drivetrain/trajectory_generator.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
TrajectoryGenerator::TrajectoryGenerator(aos::EventLoop *event_loop,
const DrivetrainConfig<double> &config)
@@ -26,6 +24,4 @@
aos::RawSender::Error::kOk);
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
diff --git a/frc971/control_loops/drivetrain/trajectory_plot.cc b/frc971/control_loops/drivetrain/trajectory_plot.cc
index 207df18..8c3ef47 100644
--- a/frc971/control_loops/drivetrain/trajectory_plot.cc
+++ b/frc971/control_loops/drivetrain/trajectory_plot.cc
@@ -40,9 +40,7 @@
namespace chrono = ::std::chrono;
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
void Main() {
const DrivetrainConfig<double> config =
@@ -229,9 +227,7 @@
}
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
int main(int argc, char **argv) {
::gflags::ParseCommandLineFlags(&argc, &argv, false);
diff --git a/frc971/control_loops/drivetrain/trajectory_test.cc b/frc971/control_loops/drivetrain/trajectory_test.cc
index 82ae312..fbf8970 100644
--- a/frc971/control_loops/drivetrain/trajectory_test.cc
+++ b/frc971/control_loops/drivetrain/trajectory_test.cc
@@ -23,10 +23,7 @@
DEFINE_string(output_file, "",
"If set, logs all channels to the provided logfile.");
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
namespace chrono = ::std::chrono;
@@ -602,7 +599,4 @@
// fast... We want to maybe replan when we get behind, or something. Maybe
// stop moving the setpoint like our 2018 arm?
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
diff --git a/frc971/control_loops/fixed_quadrature_test.cc b/frc971/control_loops/fixed_quadrature_test.cc
index 0615031..5241c08 100644
--- a/frc971/control_loops/fixed_quadrature_test.cc
+++ b/frc971/control_loops/fixed_quadrature_test.cc
@@ -4,9 +4,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// Tests that integrating y = cos(x) works.
TEST(GaussianQuadratureTest, Cos) {
@@ -28,6 +26,4 @@
::std::sin(0.5), -std::cos(0.5) + std::cos(0))));
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/flywheel/flywheel_controller.cc b/frc971/control_loops/flywheel/flywheel_controller.cc
index dc82147..aa8087f 100644
--- a/frc971/control_loops/flywheel/flywheel_controller.cc
+++ b/frc971/control_loops/flywheel/flywheel_controller.cc
@@ -3,9 +3,8 @@
#include <chrono>
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
+
+namespace frc971::control_loops::flywheel {
// Class to current limit battery current for a flywheel controller.
class CurrentLimitedStateFeedbackController
@@ -173,6 +172,4 @@
double FlywheelController::velocity() const { return loop_->X_hat(1, 0); }
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel
diff --git a/frc971/control_loops/gaussian_noise.cc b/frc971/control_loops/gaussian_noise.cc
index ddfa0f3..1d0747c 100644
--- a/frc971/control_loops/gaussian_noise.cc
+++ b/frc971/control_loops/gaussian_noise.cc
@@ -1,7 +1,6 @@
#include "frc971/control_loops/gaussian_noise.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
GaussianNoise::GaussianNoise(unsigned int seed, double stddev)
: stddev_(stddev), generator_(seed), distribution_(0.0, 1.0) {
@@ -12,5 +11,4 @@
return sample + (distribution_(generator_) * stddev_);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/hybrid_state_feedback_loop_test.cc b/frc971/control_loops/hybrid_state_feedback_loop_test.cc
index b9a0307..92f62b2 100644
--- a/frc971/control_loops/hybrid_state_feedback_loop_test.cc
+++ b/frc971/control_loops/hybrid_state_feedback_loop_test.cc
@@ -4,9 +4,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
StateFeedbackHybridPlantCoefficients<3, 1, 1>
MakeIntegralShooterPlantCoefficients() {
@@ -199,6 +197,4 @@
EXPECT_TRUE(R_discrete.isApprox(test_loop.observer().R(), 0.001));
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/jacobian_test.cc b/frc971/control_loops/jacobian_test.cc
index 57c9d7f..5606004 100644
--- a/frc971/control_loops/jacobian_test.cc
+++ b/frc971/control_loops/jacobian_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
::Eigen::Matrix<double, 4, 4> A = (::Eigen::Matrix<double, 4, 4>() << 1, 2, 4,
1, 5, 2, 3, 4, 5, 1, 3, 2, 1, 1, 3, 7)
@@ -35,6 +33,4 @@
EXPECT_TRUE(NewB.isApprox(B));
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/polytope_test.cc b/frc971/control_loops/polytope_test.cc
index 0a01248..542c981 100644
--- a/frc971/control_loops/polytope_test.cc
+++ b/frc971/control_loops/polytope_test.cc
@@ -8,8 +8,7 @@
#include "aos/testing/test_logging.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
class HPolytopeTest : public ::testing::Test {
protected:
@@ -102,5 +101,4 @@
.finished())));
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
diff --git a/frc971/control_loops/pose_test.cc b/frc971/control_loops/pose_test.cc
index 845dda7..9b3b51f 100644
--- a/frc971/control_loops/pose_test.cc
+++ b/frc971/control_loops/pose_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// Test that basic accessors on an individual Pose object work as expected.
TEST(PoseTest, BasicPoseTest) {
@@ -195,6 +193,4 @@
EXPECT_FALSE(l6.Intersects(l5));
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/position_sensor_sim.cc b/frc971/control_loops/position_sensor_sim.cc
index 222af5d..7933213 100644
--- a/frc971/control_loops/position_sensor_sim.cc
+++ b/frc971/control_loops/position_sensor_sim.cc
@@ -2,8 +2,7 @@
#include <cmath>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
/* Index pulse/segment Explanation:
*
@@ -237,5 +236,4 @@
return builder->Finish();
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/position_sensor_sim_test.cc b/frc971/control_loops/position_sensor_sim_test.cc
index 4be0dc4..2189589 100644
--- a/frc971/control_loops/position_sensor_sim_test.cc
+++ b/frc971/control_loops/position_sensor_sim_test.cc
@@ -11,8 +11,7 @@
#include "aos/die.h"
#include "frc971/control_loops/control_loops_generated.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
class PositionSensorSimTest : public ::testing::Test {
protected:
@@ -460,5 +459,4 @@
EXPECT_NEAR(position->single_turn_absolute_encoder(), 0.1, 1e-10);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/profiled_subsystem.cc b/frc971/control_loops/profiled_subsystem.cc
index 4a90bf5..dc1a377 100644
--- a/frc971/control_loops/profiled_subsystem.cc
+++ b/frc971/control_loops/profiled_subsystem.cc
@@ -1,8 +1,6 @@
#include "frc971/control_loops/profiled_subsystem.h"
-namespace frc971 {
-namespace control_loops {
-namespace internal {
+namespace frc971::control_loops::internal {
double UseUnlessZero(double target_value, double default_value) {
if (target_value != 0.0) {
@@ -12,6 +10,4 @@
}
}
-} // namespace internal
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::internal
diff --git a/frc971/control_loops/quaternion_utils.cc b/frc971/control_loops/quaternion_utils.cc
index bce78d0..dc5b411 100644
--- a/frc971/control_loops/quaternion_utils.cc
+++ b/frc971/control_loops/quaternion_utils.cc
@@ -3,8 +3,7 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
namespace {
double SinXoverX(double x) {
@@ -132,5 +131,4 @@
return result;
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
diff --git a/frc971/control_loops/quaternion_utils_test.cc b/frc971/control_loops/quaternion_utils_test.cc
index 32b1915..4e9e97a 100644
--- a/frc971/control_loops/quaternion_utils_test.cc
+++ b/frc971/control_loops/quaternion_utils_test.cc
@@ -10,9 +10,7 @@
#include "frc971/control_loops/jacobian.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace frc971 {
-namespace controls {
-namespace testing {
+namespace frc971::controls::testing {
// Tests that small perturbations around a couple quaternions averaged out
// return the original quaternion.
@@ -212,6 +210,4 @@
EXPECT_NEAR(0.0, (uz - integral3 * uz).norm(), 5e-2);
}
-} // namespace testing
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls::testing
diff --git a/frc971/control_loops/runge_kutta_test.cc b/frc971/control_loops/runge_kutta_test.cc
index e07c469..1022a47 100644
--- a/frc971/control_loops/runge_kutta_test.cc
+++ b/frc971/control_loops/runge_kutta_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// Tests that integrating dx/dt = e^x works.
TEST(RungeKuttaTest, Exponential) {
@@ -92,6 +90,4 @@
EXPECT_NEAR(y1(0, 0), RungeKuttaTimeVaryingSolution(6.0)(0, 0), 1e-7);
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
index 1fd9049..ea24ff3 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem_test.cc
@@ -22,8 +22,7 @@
using ::frc971::control_loops::PositionSensorSimulator;
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
namespace {
constexpr double kNoiseScalar = 0.01;
@@ -841,5 +840,4 @@
ZeroingErrorTest);
INSTANTIATE_TYPED_TEST_SUITE_P(My, IntakeSystemTest, TestTypes);
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/team_number_test_environment.cc b/frc971/control_loops/team_number_test_environment.cc
index a8f4ca7..1a3ccf6 100644
--- a/frc971/control_loops/team_number_test_environment.cc
+++ b/frc971/control_loops/team_number_test_environment.cc
@@ -2,14 +2,10 @@
#include "aos/network/team_number.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
void TeamNumberEnvironment::SetUp() {
::aos::network::OverrideTeamNumber(kTeamNumber);
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
diff --git a/frc971/control_loops/voltage_cap/voltage_cap.cc b/frc971/control_loops/voltage_cap/voltage_cap.cc
index d6d8456..aab355c 100644
--- a/frc971/control_loops/voltage_cap/voltage_cap.cc
+++ b/frc971/control_loops/voltage_cap/voltage_cap.cc
@@ -2,8 +2,7 @@
#include <limits>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
void VoltageCap(double max_voltage, double voltage_one, double voltage_two,
double *out_voltage_one, double *out_voltage_two) {
@@ -91,5 +90,4 @@
VoltageCap(12.0, voltage_one, voltage_two, out_voltage_one, out_voltage_two);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
diff --git a/frc971/control_loops/voltage_cap/voltage_cap_test.cc b/frc971/control_loops/voltage_cap/voltage_cap_test.cc
index ea812b9..b77d107 100644
--- a/frc971/control_loops/voltage_cap/voltage_cap_test.cc
+++ b/frc971/control_loops/voltage_cap/voltage_cap_test.cc
@@ -4,9 +4,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
class VoltageTest : public ::testing::Test {};
@@ -240,6 +238,4 @@
EXPECT_EQ(5.0, voltage_two);
}
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing