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/analysis/in_process_plotter.cc b/frc971/analysis/in_process_plotter.cc
index b327c54..b537aa4 100644
--- a/frc971/analysis/in_process_plotter.cc
+++ b/frc971/analysis/in_process_plotter.cc
@@ -2,8 +2,7 @@
#include "aos/configuration.h"
-namespace frc971 {
-namespace analysis {
+namespace frc971::analysis {
namespace {
const char *kDataPath = "frc971/analysis/cpp_plot";
@@ -168,5 +167,4 @@
next_top_ = 0;
}
-} // namespace analysis
-} // namespace frc971
+} // namespace frc971::analysis
diff --git a/frc971/analysis/py_log_reader.cc b/frc971/analysis/py_log_reader.cc
index 6ee6c69..57d57d0 100644
--- a/frc971/analysis/py_log_reader.cc
+++ b/frc971/analysis/py_log_reader.cc
@@ -27,8 +27,7 @@
#include "aos/init.h"
#include "aos/json_to_flatbuffer.h"
-namespace frc971 {
-namespace analysis {
+namespace frc971::analysis {
namespace {
// All the data corresponding to a single message.
@@ -300,8 +299,7 @@
}
} // namespace
-} // namespace analysis
-} // namespace frc971
+} // namespace frc971::analysis
PyMODINIT_FUNC PyInit_py_log_reader(void) {
return frc971::analysis::InitModule();
diff --git a/frc971/autonomous/base_autonomous_actor.cc b/frc971/autonomous/base_autonomous_actor.cc
index 22909be..2156045 100644
--- a/frc971/autonomous/base_autonomous_actor.cc
+++ b/frc971/autonomous/base_autonomous_actor.cc
@@ -18,8 +18,7 @@
namespace this_thread = ::std::this_thread;
namespace drivetrain = frc971::control_loops::drivetrain;
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
BaseAutonomousActor::BaseAutonomousActor(
::aos::EventLoop *event_loop,
@@ -678,5 +677,4 @@
}
}
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
diff --git a/frc971/can_logger/asc_logger.cc b/frc971/can_logger/asc_logger.cc
index 96b2e96..6848938 100644
--- a/frc971/can_logger/asc_logger.cc
+++ b/frc971/can_logger/asc_logger.cc
@@ -2,8 +2,7 @@
#include <linux/can.h>
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
AscLogger::AscLogger(aos::EventLoop *event_loop, const std::string &filename)
: output_(filename), event_loop_(event_loop) {
@@ -138,5 +137,4 @@
file << "\n";
}
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
diff --git a/frc971/can_logger/can_logger.cc b/frc971/can_logger/can_logger.cc
index 7a6c0fe..e7e1e6f 100644
--- a/frc971/can_logger/can_logger.cc
+++ b/frc971/can_logger/can_logger.cc
@@ -1,7 +1,6 @@
#include "frc971/can_logger/can_logger.h"
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
CanLogger::CanLogger(aos::ShmEventLoop *event_loop,
std::string_view channel_name,
@@ -84,5 +83,4 @@
return true;
}
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
diff --git a/frc971/codelab/basic.cc b/frc971/codelab/basic.cc
index 66f08f9..a78da41 100644
--- a/frc971/codelab/basic.cc
+++ b/frc971/codelab/basic.cc
@@ -1,7 +1,6 @@
#include "frc971/codelab/basic.h"
-namespace frc971 {
-namespace codelab {
+namespace frc971::codelab {
Basic::Basic(::aos::EventLoop *event_loop, const ::std::string &name)
: frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
@@ -45,5 +44,4 @@
}
}
-} // namespace codelab
-} // namespace frc971
+} // namespace frc971::codelab
diff --git a/frc971/codelab/basic_test.cc b/frc971/codelab/basic_test.cc
index e9820bc..b2ad83e 100644
--- a/frc971/codelab/basic_test.cc
+++ b/frc971/codelab/basic_test.cc
@@ -18,9 +18,7 @@
#include "frc971/control_loops/control_loop_test.h"
#include "frc971/control_loops/team_number_test_environment.h"
-namespace frc971 {
-namespace codelab {
-namespace testing {
+namespace frc971::codelab::testing {
namespace chrono = ::std::chrono;
using aos::monotonic_clock;
@@ -238,6 +236,4 @@
basic_simulation_.VerifyResults(0.0, false);
}
-} // namespace testing
-} // namespace codelab
-} // namespace frc971
+} // namespace frc971::codelab::testing
diff --git a/frc971/constants.h b/frc971/constants.h
index 0367937..48b8ca9 100644
--- a/frc971/constants.h
+++ b/frc971/constants.h
@@ -6,8 +6,7 @@
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/zeroing/constants_generated.h"
-namespace frc971 {
-namespace constants {
+namespace frc971::constants {
typedef frc971::zeroing::HallEffectZeroingConstantsT HallEffectZeroingConstants;
@@ -53,7 +52,6 @@
}
};
-} // namespace constants
-} // namespace frc971
+} // namespace frc971::constants
#endif // FRC971_CONSTANTS_H_
diff --git a/frc971/constants/constants_sender_test.cc b/frc971/constants/constants_sender_test.cc
index 5e551c1..e4920d3 100644
--- a/frc971/constants/constants_sender_test.cc
+++ b/frc971/constants/constants_sender_test.cc
@@ -11,8 +11,7 @@
#include "frc971/constants/testdata/constants_data_generated.h"
#include "frc971/constants/testdata/constants_list_generated.h"
-namespace frc971::constants {
-namespace testing {
+namespace frc971::constants::testing {
using aos::testing::ArtifactPath;
@@ -121,5 +120,4 @@
"Invalid field name");
}
-} // namespace testing
-} // namespace frc971::constants
+} // namespace frc971::constants::testing
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
diff --git a/frc971/input/action_joystick_input.cc b/frc971/input/action_joystick_input.cc
index dfd229e..ae3346c 100644
--- a/frc971/input/action_joystick_input.cc
+++ b/frc971/input/action_joystick_input.cc
@@ -8,8 +8,7 @@
using ::frc971::input::driver_station::ControlBit;
-namespace frc971 {
-namespace input {
+namespace frc971::input {
void ActionJoystickInput::RunIteration(
const ::frc971::input::driver_station::Data &unsorted_data) {
@@ -74,5 +73,4 @@
AutoEnded();
}
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
diff --git a/frc971/input/driver_station_data.cc b/frc971/input/driver_station_data.cc
index 18d96fd..06d2d69 100644
--- a/frc971/input/driver_station_data.cc
+++ b/frc971/input/driver_station_data.cc
@@ -2,9 +2,7 @@
#include "glog/logging.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
Data::Data() : current_values_(), old_values_() {}
@@ -119,6 +117,4 @@
return current_values_.joysticks[axis.joystick() - 1].axis[axis.number() - 1];
}
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
diff --git a/frc971/input/drivetrain_input.cc b/frc971/input/drivetrain_input.cc
index 5aedd0e..be61cc4 100644
--- a/frc971/input/drivetrain_input.cc
+++ b/frc971/input/drivetrain_input.cc
@@ -18,8 +18,7 @@
namespace drivetrain = frc971::control_loops::drivetrain;
-namespace frc971 {
-namespace input {
+namespace frc971::input {
const ButtonLocation kShiftHigh(2, 3), kShiftHigh2(2, 2), kShiftLow(2, 1);
@@ -371,5 +370,4 @@
return drivetrain_input_reader;
}
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
diff --git a/frc971/input/joystick_input.cc b/frc971/input/joystick_input.cc
index d0d9bc0..19eaa37 100644
--- a/frc971/input/joystick_input.cc
+++ b/frc971/input/joystick_input.cc
@@ -6,8 +6,7 @@
#include "aos/logging/logging.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
void JoystickInput::HandleData(const ::aos::JoystickState *joystick_state) {
data_.Update(joystick_state);
@@ -60,5 +59,4 @@
RunIteration(data_);
}
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
diff --git a/frc971/input/redundant_joystick_data.cc b/frc971/input/redundant_joystick_data.cc
index a25e6c3..752239d 100644
--- a/frc971/input/redundant_joystick_data.cc
+++ b/frc971/input/redundant_joystick_data.cc
@@ -2,9 +2,7 @@
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
RedundantData::RedundantData(const Data &data) : joystick_map_(), data_(data) {
// Start with a naive map.
@@ -98,6 +96,4 @@
return data_.GetAxis(mapped_location);
}
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
diff --git a/frc971/orin/apriltag.cc b/frc971/orin/apriltag.cc
index 1cb0f88..dd253d1 100644
--- a/frc971/orin/apriltag.cc
+++ b/frc971/orin/apriltag.cc
@@ -22,8 +22,7 @@
#include "frc971/orin/threshold.h"
#include "frc971/orin/transform_output_iterator.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
namespace {
typedef std::chrono::duration<float, std::milli> float_milli;
@@ -1151,5 +1150,4 @@
first_ = false;
}
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/apriltag_detect.cc b/frc971/orin/apriltag_detect.cc
index eecc056..69c93cc 100644
--- a/frc971/orin/apriltag_detect.cc
+++ b/frc971/orin/apriltag_detect.cc
@@ -31,8 +31,7 @@
zarray_t *poly1);
};
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
namespace {
void HostFitLine(LineFitMoments moments, double *lineparam01,
@@ -519,5 +518,4 @@
zarray_sort(detections_, detection_compare_function);
}
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/crcv_generator.cc b/frc971/orin/crcv_generator.cc
index 5c72385..a3f1f03 100644
--- a/frc971/orin/crcv_generator.cc
+++ b/frc971/orin/crcv_generator.cc
@@ -15,8 +15,8 @@
// ahead-of-time optimized functions as directed by command-line arguments.
// https://halide-lang.org/tutorials/tutorial_lesson_15_generators.html has an
// introduction to much of the magic in this file.
-namespace frc971 {
-namespace orin {
+
+namespace frc971::orin {
namespace {
template <typename T>
@@ -142,8 +142,7 @@
}
};
-} // namespace orin
-} // namespace frc971
+} // namespace frc971::orin
HALIDE_REGISTER_GENERATOR(frc971::orin::YCbCr, ycbcr)
HALIDE_REGISTER_GENERATOR(frc971::orin::YCbCr422, ycbcr422)
diff --git a/frc971/orin/cuda.cc b/frc971/orin/cuda.cc
index 89b1529..6bcc79c 100644
--- a/frc971/orin/cuda.cc
+++ b/frc971/orin/cuda.cc
@@ -7,8 +7,7 @@
sync, false,
"If true, force synchronization after each step to isolate errors better.");
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
size_t overall_memory = 0;
@@ -25,5 +24,4 @@
if (FLAGS_sync) CheckAndSynchronize(message);
}
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/line_fit_filter.cc b/frc971/orin/line_fit_filter.cc
index 954976a..737079f 100644
--- a/frc971/orin/line_fit_filter.cc
+++ b/frc971/orin/line_fit_filter.cc
@@ -8,8 +8,7 @@
// #define DEBUG_BLOB_NUMBER 401
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
static_assert(sizeof(LineFitPoint) == 40, "Size of LineFitPoint changed");
static_assert(sizeof(int4) == 16, "Size of int4 changed");
@@ -1231,5 +1230,4 @@
return os;
}
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/points.cc b/frc971/orin/points.cc
index dbf5496..7dc36f2 100644
--- a/frc971/orin/points.cc
+++ b/frc971/orin/points.cc
@@ -3,8 +3,7 @@
#include <iomanip>
#include <ostream>
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
std::ostream &operator<<(std::ostream &os, const QuadBoundaryPoint &point) {
std::ios_base::fmtflags original_flags = os.flags();
@@ -31,5 +30,4 @@
static_assert(sizeof(IndexPoint) == 8, "IndexPoint didn't pack right.");
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/threshold.cc b/frc971/orin/threshold.cc
index 79ccced..4254b71 100644
--- a/frc971/orin/threshold.cc
+++ b/frc971/orin/threshold.cc
@@ -4,8 +4,7 @@
#include "frc971/orin/cuda.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
namespace {
// 1280 -> 2 * 128 * 5
@@ -202,5 +201,4 @@
}
}
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
diff --git a/frc971/orin/transform_output_iterator.h b/frc971/orin/transform_output_iterator.h
index 051baea..cdda637 100644
--- a/frc971/orin/transform_output_iterator.h
+++ b/frc971/orin/transform_output_iterator.h
@@ -1,8 +1,7 @@
#ifndef FRC971_TRANSFORM_OUTPUT_ITERATOR_
#define FRC971_TRANSFORM_OUTPUT_ITERATOR_
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// template class that allows conversions at the output of a cub algorithm
template <typename InputType, typename OutputType, typename ConversionOp,
@@ -86,7 +85,6 @@
OutputType *ptr;
};
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_TRANSFORM_OUTPUT_ITERATOR_
diff --git a/frc971/shifter_hall_effect.h b/frc971/shifter_hall_effect.h
index 991386d..4a0197c 100644
--- a/frc971/shifter_hall_effect.h
+++ b/frc971/shifter_hall_effect.h
@@ -1,8 +1,7 @@
#ifndef FRC971_SHIFTER_HALL_EFFECT_H_
#define FRC971_SHIFTER_HALL_EFFECT_H_
-namespace frc971 {
-namespace constants {
+namespace frc971::constants {
// Contains the constants for mapping the analog voltages that the shifter
// sensors return to the shifter position. The code which uses this is trying
@@ -28,7 +27,6 @@
double high_gear_middle;
};
-} // namespace constants
-} // namespace frc971
+} // namespace frc971::constants
#endif
diff --git a/frc971/shooter_interpolation/interpolation.cc b/frc971/shooter_interpolation/interpolation.cc
index 66b2cf9..1faa046 100644
--- a/frc971/shooter_interpolation/interpolation.cc
+++ b/frc971/shooter_interpolation/interpolation.cc
@@ -4,12 +4,10 @@
#include <utility>
#include <vector>
-namespace frc971 {
-namespace shooter_interpolation {
+namespace frc971::shooter_interpolation {
double Blend(double coefficient, double a1, double a2) {
return (1 - coefficient) * a1 + coefficient * a2;
}
-} // namespace shooter_interpolation
-} // namespace frc971
+} // namespace frc971::shooter_interpolation
diff --git a/frc971/shooter_interpolation/interpolation_test.cc b/frc971/shooter_interpolation/interpolation_test.cc
index 92a2b76..3409282 100644
--- a/frc971/shooter_interpolation/interpolation_test.cc
+++ b/frc971/shooter_interpolation/interpolation_test.cc
@@ -8,8 +8,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace shooter_interpolation {
+namespace frc971::shooter_interpolation {
struct TestShotParams {
double angle;
@@ -72,5 +71,4 @@
ASSERT_EQ(TestShotParams({10, 567.323}), interpolation.Get(5));
}
-} // namespace shooter_interpolation
-} // namespace frc971
+} // namespace frc971::shooter_interpolation
diff --git a/frc971/solvers/convex_test.cc b/frc971/solvers/convex_test.cc
index 213e70b..21f2f8c 100644
--- a/frc971/solvers/convex_test.cc
+++ b/frc971/solvers/convex_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace solvers {
-namespace testing {
+namespace frc971::solvers::testing {
const Eigen::IOFormat kHeavyFormat(Eigen::StreamPrecision, 0, ", ",
",\n "
@@ -101,6 +99,4 @@
EXPECT_NEAR((result - Eigen::Vector2d(4.0, 4.0)).norm(), 0.0, 1e-6);
}
-} // namespace testing
-} // namespace solvers
-} // namespace frc971
+} // namespace frc971::solvers::testing
diff --git a/frc971/solvers/sparse_convex.cc b/frc971/solvers/sparse_convex.cc
index 7e2a6ca..714b21c 100644
--- a/frc971/solvers/sparse_convex.cc
+++ b/frc971/solvers/sparse_convex.cc
@@ -5,8 +5,7 @@
#include <Eigen/Sparse>
#include <Eigen/SparseLU>
-namespace frc971 {
-namespace solvers {
+namespace frc971::solvers {
Eigen::VectorXd SparseSolver::Rt(const Derivatives &derivatives,
Eigen::VectorXd y, double t_inverse) {
@@ -356,5 +355,4 @@
}
}
-} // namespace solvers
-} // namespace frc971
+} // namespace frc971::solvers
diff --git a/frc971/solvers/sparse_convex_test.cc b/frc971/solvers/sparse_convex_test.cc
index 63a9409..490e8e2 100644
--- a/frc971/solvers/sparse_convex_test.cc
+++ b/frc971/solvers/sparse_convex_test.cc
@@ -2,9 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace solvers {
-namespace testing {
+namespace frc971::solvers::testing {
const Eigen::IOFormat kHeavyFormat(Eigen::StreamPrecision, 0, ", ",
",\n "
@@ -98,6 +96,4 @@
EXPECT_NEAR((result - Eigen::Vector2d(4.0, 4.0)).norm(), 0.0, 1e-6);
}
-} // namespace testing
-} // namespace solvers
-} // namespace frc971
+} // namespace frc971::solvers::testing
diff --git a/frc971/vision/calibration_accumulator.cc b/frc971/vision/calibration_accumulator.cc
index 3b0bcc6..d8abd33 100644
--- a/frc971/vision/calibration_accumulator.cc
+++ b/frc971/vision/calibration_accumulator.cc
@@ -21,8 +21,7 @@
DEFINE_bool(save_valid_only, false,
"If true, only save images with valid pose estimates");
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
using aos::distributed_clock;
using aos::monotonic_clock;
namespace chrono = std::chrono;
@@ -278,5 +277,4 @@
gyro, accel * kG);
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/charuco_lib.cc b/frc971/vision/charuco_lib.cc
index 8e8acc3..c24d02c 100644
--- a/frc971/vision/charuco_lib.cc
+++ b/frc971/vision/charuco_lib.cc
@@ -38,8 +38,7 @@
DECLARE_bool(enable_ftrace);
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
namespace chrono = std::chrono;
using aos::monotonic_clock;
@@ -600,5 +599,4 @@
return os;
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/extrinsics_calibration.cc b/frc971/vision/extrinsics_calibration.cc
index 9459c84..6017258 100644
--- a/frc971/vision/extrinsics_calibration.cc
+++ b/frc971/vision/extrinsics_calibration.cc
@@ -14,8 +14,7 @@
#include "frc971/vision/charuco_lib.h"
#include "frc971/vision/visualize_robot.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
namespace chrono = std::chrono;
using aos::distributed_clock;
@@ -1008,5 +1007,4 @@
filter.Visualize(calibration_parameters);
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/intrinsics_calibration.cc b/frc971/vision/intrinsics_calibration.cc
index 452dd74..b4d3825 100644
--- a/frc971/vision/intrinsics_calibration.cc
+++ b/frc971/vision/intrinsics_calibration.cc
@@ -23,8 +23,7 @@
"Intrinsics to use for estimating board pose prior to solving "
"for the new intrinsics.");
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
namespace {
void Main() {
@@ -52,8 +51,7 @@
}
} // namespace
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
diff --git a/frc971/vision/intrinsics_calibration_lib.cc b/frc971/vision/intrinsics_calibration_lib.cc
index 6cf53e8..ab03e01 100644
--- a/frc971/vision/intrinsics_calibration_lib.cc
+++ b/frc971/vision/intrinsics_calibration_lib.cc
@@ -1,7 +1,6 @@
#include "frc971/vision/intrinsics_calibration_lib.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
IntrinsicsCalibration::IntrinsicsCalibration(
aos::EventLoop *event_loop, std::string_view pi, std::string_view camera_id,
@@ -241,5 +240,4 @@
LOG(INFO) << "Skipping calibration due to not enough images.";
}
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/media_device.cc b/frc971/vision/media_device.cc
index a369cfb..46f3419 100644
--- a/frc971/vision/media_device.cc
+++ b/frc971/vision/media_device.cc
@@ -20,8 +20,7 @@
#include "aos/scoped/scoped_fd.h"
#include "aos/util/file.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
void Entity::Log() const {
LOG(INFO) << " { \"id\": " << id() << ",";
@@ -408,5 +407,4 @@
}
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/v4l2_reader.cc b/frc971/vision/v4l2_reader.cc
index 1404ec5..2d67c9c 100644
--- a/frc971/vision/v4l2_reader.cc
+++ b/frc971/vision/v4l2_reader.cc
@@ -9,8 +9,7 @@
DEFINE_bool(ignore_timestamps, false,
"Don't require timestamps on images. Used to allow webcams");
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
V4L2ReaderBase::V4L2ReaderBase(aos::EventLoop *event_loop,
std::string_view device_name,
@@ -401,5 +400,4 @@
PCHECK(ImageSensorIoctl(VIDIOC_S_EXT_CTRLS, &controls) == 0);
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/visualize_robot.cc b/frc971/vision/visualize_robot.cc
index 0c7a536..d13668e 100644
--- a/frc971/vision/visualize_robot.cc
+++ b/frc971/vision/visualize_robot.cc
@@ -6,8 +6,7 @@
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc.hpp>
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
void VisualizeRobot::SetDefaultViewpoint(int image_width, double focal_length) {
// 10 meters above the origin, rotated so the camera faces straight down
@@ -106,5 +105,4 @@
DrawLine(rr_corner, fr_corner, color);
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
diff --git a/frc971/vision/visualize_robot_sample.cc b/frc971/vision/visualize_robot_sample.cc
index 6ca7a9c..ad1d6b6 100644
--- a/frc971/vision/visualize_robot_sample.cc
+++ b/frc971/vision/visualize_robot_sample.cc
@@ -14,8 +14,7 @@
#include "aos/time/time.h"
#include "frc971/vision/visualize_robot.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Show / test the basics of visualizing the robot frames
void Main(int /*argc*/, char ** /* argv */) {
@@ -45,8 +44,7 @@
cv::imshow("Display", image_mat);
cv::waitKey();
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index 597c5e8..c8aadfd 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -11,8 +11,7 @@
#include "aos/time/time.h"
#include "frc971/wpilib/imu_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
using ::aos::monotonic_clock;
namespace chrono = ::std::chrono;
@@ -424,5 +423,4 @@
return true;
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/ADIS16470.cc b/frc971/wpilib/ADIS16470.cc
index 1612ee8..0b3d45c 100644
--- a/frc971/wpilib/ADIS16470.cc
+++ b/frc971/wpilib/ADIS16470.cc
@@ -8,8 +8,7 @@
#include "aos/time/time.h"
#include "hal/HAL.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
namespace {
namespace chrono = std::chrono;
namespace registers {
@@ -516,5 +515,4 @@
spi_->Write(buffer2, sizeof(buffer2));
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/buffered_pcm.cc b/frc971/wpilib/buffered_pcm.cc
index f356722..c64bbdc 100644
--- a/frc971/wpilib/buffered_pcm.cc
+++ b/frc971/wpilib/buffered_pcm.cc
@@ -7,8 +7,7 @@
#include "hal/HAL.h"
#include "hal/Ports.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
BufferedPcm::BufferedPcm(int module) : module_(module) {
for (int i = 0; i < 8; ++i) {
@@ -53,5 +52,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/buffered_solenoid.cc b/frc971/wpilib/buffered_solenoid.cc
index a4b337e..f6defcb 100644
--- a/frc971/wpilib/buffered_solenoid.cc
+++ b/frc971/wpilib/buffered_solenoid.cc
@@ -2,10 +2,8 @@
#include "frc971/wpilib/buffered_pcm.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
void BufferedSolenoid::Set(bool value) { pcm_->DoSet(number_, value); }
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/buffered_solenoid.h b/frc971/wpilib/buffered_solenoid.h
index f0a4c11..1f127c5 100644
--- a/frc971/wpilib/buffered_solenoid.h
+++ b/frc971/wpilib/buffered_solenoid.h
@@ -1,8 +1,7 @@
#ifndef FRC971_WPILIB_BUFFERED_SOLENOID_H_
#define FRC971_WPILIB_BUFFERED_SOLENOID_H_
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class BufferedPcm;
@@ -22,7 +21,6 @@
friend class BufferedPcm;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_BUFFERED_SOLENOID_H_
diff --git a/frc971/wpilib/dma_edge_counting.cc b/frc971/wpilib/dma_edge_counting.cc
index 4e8a158..c84bc15 100644
--- a/frc971/wpilib/dma_edge_counting.cc
+++ b/frc971/wpilib/dma_edge_counting.cc
@@ -2,8 +2,7 @@
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
bool DMAEdgeCounter::ExtractValue(const DMASample &sample) const {
return sample.Get(input_);
@@ -101,5 +100,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/drivetrain_writer.cc b/frc971/wpilib/drivetrain_writer.cc
index 0afbe20..2966481 100644
--- a/frc971/wpilib/drivetrain_writer.cc
+++ b/frc971/wpilib/drivetrain_writer.cc
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/PWM.h"
#include "frc971/wpilib/loop_output_handler.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
void DrivetrainWriter::Write(
const ::frc971::control_loops::drivetrain::Output &output) {
@@ -39,5 +38,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/encoder_and_potentiometer.cc b/frc971/wpilib/encoder_and_potentiometer.cc
index 578fb96..8a94e15 100644
--- a/frc971/wpilib/encoder_and_potentiometer.cc
+++ b/frc971/wpilib/encoder_and_potentiometer.cc
@@ -3,8 +3,7 @@
#include "aos/logging/logging.h"
#include "aos/realtime.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
bool DMAEncoder::DoUpdateFromSample(const DMASample &sample) {
if (index_last_value_) {
@@ -20,5 +19,4 @@
return false;
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/fpga_time_conversion.cc b/frc971/wpilib/fpga_time_conversion.cc
index 6f9a267..3ca9984 100644
--- a/frc971/wpilib/fpga_time_conversion.cc
+++ b/frc971/wpilib/fpga_time_conversion.cc
@@ -2,8 +2,7 @@
#include "aos/util/compiler_memory_barrier.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
std::optional<std::chrono::nanoseconds> CalculateFpgaOffset() {
aos_compiler_memory_barrier();
@@ -32,5 +31,4 @@
return monotonic_now.time_since_epoch() - fpga_average;
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/gyro_interface.cc b/frc971/wpilib/gyro_interface.cc
index a90e95a..eb23b48 100644
--- a/frc971/wpilib/gyro_interface.cc
+++ b/frc971/wpilib/gyro_interface.cc
@@ -10,8 +10,7 @@
#define M_PI 3.14159265358979323846
#endif
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
GyroInterface::GyroInterface() : gyro_(new frc::SPI(frc::SPI::kOnboardCS0)) {
// The gyro goes up to 8.08MHz.
@@ -146,5 +145,4 @@
return result;
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/gyro_sender.cc b/frc971/wpilib/gyro_sender.cc
index ac88acb..934daf8 100644
--- a/frc971/wpilib/gyro_sender.cc
+++ b/frc971/wpilib/gyro_sender.cc
@@ -16,8 +16,7 @@
#include "frc971/queues/gyro_uid_generated.h"
#include "frc971/zeroing/averager.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
namespace chrono = ::std::chrono;
using ::aos::monotonic_clock;
@@ -145,5 +144,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/interrupt_edge_counting.cc b/frc971/wpilib/interrupt_edge_counting.cc
index 9b63b84..4fc2172 100644
--- a/frc971/wpilib/interrupt_edge_counting.cc
+++ b/frc971/wpilib/interrupt_edge_counting.cc
@@ -5,8 +5,7 @@
#include "aos/realtime.h"
#include "aos/time/time.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
void EdgeCounter::GatherPolledValue() {
shadow_values_.polled_value = input_->Get();
@@ -103,5 +102,4 @@
return true;
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index 26f7545..f3b97f6 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -8,8 +8,7 @@
#include "frc971/wpilib/ahal/DriverStation.h"
#include "hal/HAL.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
using aos::Joystick;
@@ -138,5 +137,4 @@
});
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/loop_output_handler_test.cc b/frc971/wpilib/loop_output_handler_test.cc
index b3fbb0d..f3b4aef 100644
--- a/frc971/wpilib/loop_output_handler_test.cc
+++ b/frc971/wpilib/loop_output_handler_test.cc
@@ -10,9 +10,7 @@
#include "aos/time/time.h"
#include "frc971/wpilib/loop_output_handler_test_generated.h"
-namespace frc971 {
-namespace wpilib {
-namespace testing {
+namespace frc971::wpilib::testing {
namespace {
namespace chrono = ::std::chrono;
using ::aos::monotonic_clock;
@@ -118,6 +116,4 @@
loop_output.last_time() + chrono::milliseconds(100));
}
-} // namespace testing
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib::testing
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 0526806..5b02bb5 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -8,8 +8,7 @@
#include "frc971/wpilib/ahal/PowerDistributionPanel.h"
#include "frc971/wpilib/pdp_values_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
namespace chrono = ::std::chrono;
@@ -50,5 +49,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/sensor_reader.cc b/frc971/wpilib/sensor_reader.cc
index 1486042..447e3b4 100644
--- a/frc971/wpilib/sensor_reader.cc
+++ b/frc971/wpilib/sensor_reader.cc
@@ -17,8 +17,7 @@
DEFINE_int32(pwm_offset, 5050 / 2,
"Offset of reading the sensors from the start of the PWM cycle");
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
SensorReader::SensorReader(::aos::ShmEventLoop *event_loop)
: event_loop_(event_loop),
@@ -180,5 +179,4 @@
}
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/spi_rx_clearer.cc b/frc971/wpilib/spi_rx_clearer.cc
index 1faa3f6..09bbbc8 100644
--- a/frc971/wpilib/spi_rx_clearer.cc
+++ b/frc971/wpilib/spi_rx_clearer.cc
@@ -8,8 +8,7 @@
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
SpiRxClearer::SpiRxClearer() {
const int fd = AOS_PCHECK(open("/dev/mem", O_RDWR));
@@ -40,5 +39,4 @@
AOS_LOG(FATAL, "Failed to clear the RX FIFO\n");
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/wpilib_interface.cc b/frc971/wpilib/wpilib_interface.cc
index d1703ce..f5825c8 100644
--- a/frc971/wpilib/wpilib_interface.cc
+++ b/frc971/wpilib/wpilib_interface.cc
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/Utility.h"
#include "hal/HAL.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
flatbuffers::Offset<aos::RobotState> PopulateRobotState(
aos::Sender<::aos::RobotState>::Builder *builder, int32_t my_pid) {
@@ -36,5 +35,4 @@
return robot_state_builder.Finish();
}
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/wpilib_utils.cc b/frc971/wpilib/wpilib_utils.cc
index 937acd9..d6bc696 100644
--- a/frc971/wpilib/wpilib_utils.cc
+++ b/frc971/wpilib/wpilib_utils.cc
@@ -1,7 +1,6 @@
#include "frc971/wpilib/wpilib_utils.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
bool SafePotVoltageRange(::frc971::constants::Range subsystem_range,
double potentiometer_offset,
@@ -22,5 +21,4 @@
(kMinVoltage + limit_buffer) < max_range_voltage &&
max_range_voltage < (kMaxVoltage - limit_buffer));
}
-} // namespace wpilib
-} // namespace frc971
\ No newline at end of file
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/wpilib_utils_test.cc b/frc971/wpilib/wpilib_utils_test.cc
index 2b21438..e9781b9 100644
--- a/frc971/wpilib/wpilib_utils_test.cc
+++ b/frc971/wpilib/wpilib_utils_test.cc
@@ -4,9 +4,7 @@
#include "aos/testing/test_logging.h"
#include "frc971/constants.h"
-namespace frc971 {
-namespace wpilib {
-namespace testing {
+namespace frc971::wpilib::testing {
namespace {
double climber_pot_translate_inverse_test(double position) {
@@ -153,6 +151,4 @@
}
} // namespace
-} // namespace testing
-} // namespace wpilib
-} // namespace frc971
\ No newline at end of file
+} // namespace frc971::wpilib::testing
diff --git a/frc971/zeroing/absolute_and_absolute_encoder.cc b/frc971/zeroing/absolute_and_absolute_encoder.cc
index 03ef3f1..b9ba33d 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder.cc
+++ b/frc971/zeroing/absolute_and_absolute_encoder.cc
@@ -8,8 +8,7 @@
#include "aos/logging/logging.h"
#include "frc971/zeroing/wrap.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
AbsoluteAndAbsoluteEncoderZeroingEstimator::
AbsoluteAndAbsoluteEncoderZeroingEstimator(
@@ -234,5 +233,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/absolute_and_absolute_encoder_test.cc b/frc971/zeroing/absolute_and_absolute_encoder_test.cc
index 5dac38b..08ab924 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder_test.cc
+++ b/frc971/zeroing/absolute_and_absolute_encoder_test.cc
@@ -6,9 +6,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::AbsoluteAndAbsoluteEncoderZeroingConstants;
@@ -343,6 +341,4 @@
::testing::ElementsAre(ZeroingError::OFFSET_MOVED_TOO_FAR));
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/absolute_encoder.cc b/frc971/zeroing/absolute_encoder.cc
index aa68acf..f5e3e3d 100644
--- a/frc971/zeroing/absolute_encoder.cc
+++ b/frc971/zeroing/absolute_encoder.cc
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
AbsoluteEncoderZeroingEstimator::AbsoluteEncoderZeroingEstimator(
const constants::AbsoluteEncoderZeroingConstants &constants)
@@ -181,5 +180,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/absolute_encoder_test.cc b/frc971/zeroing/absolute_encoder_test.cc
index 6e78faa..aa2fb9f 100644
--- a/frc971/zeroing/absolute_encoder_test.cc
+++ b/frc971/zeroing/absolute_encoder_test.cc
@@ -5,9 +5,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::AbsoluteEncoderZeroingConstants;
@@ -169,6 +167,4 @@
::testing::ElementsAre(ZeroingError::LOST_ABSOLUTE_ENCODER));
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/averager_test.cc b/frc971/zeroing/averager_test.cc
index 50eac72..d4f154a 100644
--- a/frc971/zeroing/averager_test.cc
+++ b/frc971/zeroing/averager_test.cc
@@ -2,8 +2,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
class AveragerTest : public ::testing::Test {
protected:
@@ -57,5 +56,4 @@
ASSERT_EQ(0.0, averager.GetAverage()(0, 0));
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/continuous_absolute_encoder.cc b/frc971/zeroing/continuous_absolute_encoder.cc
index a47a491..ebaf101 100644
--- a/frc971/zeroing/continuous_absolute_encoder.cc
+++ b/frc971/zeroing/continuous_absolute_encoder.cc
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
ContinuousAbsoluteEncoderZeroingEstimator::
ContinuousAbsoluteEncoderZeroingEstimator(
@@ -165,5 +164,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/continuous_absolute_encoder_test.cc b/frc971/zeroing/continuous_absolute_encoder_test.cc
index 75d6de0..f0b1415 100644
--- a/frc971/zeroing/continuous_absolute_encoder_test.cc
+++ b/frc971/zeroing/continuous_absolute_encoder_test.cc
@@ -6,9 +6,7 @@
#include "frc971/zeroing/wrap.h"
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::ContinuousAbsoluteEncoderZeroingConstants;
@@ -193,6 +191,4 @@
::testing::ElementsAre(ZeroingError::LOST_ABSOLUTE_ENCODER));
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/hall_effect_and_position.cc b/frc971/zeroing/hall_effect_and_position.cc
index e074668..99454e4 100644
--- a/frc971/zeroing/hall_effect_and_position.cc
+++ b/frc971/zeroing/hall_effect_and_position.cc
@@ -6,8 +6,7 @@
#include "glog/logging.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
HallEffectAndPositionZeroingEstimator::HallEffectAndPositionZeroingEstimator(
const ZeroingConstants &constants)
@@ -123,5 +122,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/hall_effect_and_position_test.cc b/frc971/zeroing/hall_effect_and_position_test.cc
index c9ddf65..d49d900 100644
--- a/frc971/zeroing/hall_effect_and_position_test.cc
+++ b/frc971/zeroing/hall_effect_and_position_test.cc
@@ -4,9 +4,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
class HallEffectAndPositionZeroingTest : public ZeroingTest {
protected:
@@ -130,6 +128,4 @@
EXPECT_FALSE(estimator.zeroed());
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/pot_and_absolute_encoder.cc b/frc971/zeroing/pot_and_absolute_encoder.cc
index f62b393..bef6f2d 100644
--- a/frc971/zeroing/pot_and_absolute_encoder.cc
+++ b/frc971/zeroing/pot_and_absolute_encoder.cc
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/wrap.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
PotAndAbsoluteEncoderZeroingEstimator::PotAndAbsoluteEncoderZeroingEstimator(
const constants::PotAndAbsoluteEncoderZeroingConstants &constants)
@@ -200,5 +199,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/pot_and_absolute_encoder_test.cc b/frc971/zeroing/pot_and_absolute_encoder_test.cc
index 4cd3821..00e69bf 100644
--- a/frc971/zeroing/pot_and_absolute_encoder_test.cc
+++ b/frc971/zeroing/pot_and_absolute_encoder_test.cc
@@ -5,9 +5,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::PotAndAbsoluteEncoderZeroingConstants;
@@ -149,6 +147,4 @@
::testing::ElementsAre(ZeroingError::LOST_ABSOLUTE_ENCODER));
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/pot_and_index.cc b/frc971/zeroing/pot_and_index.cc
index 0f1e9e0..fb82f22 100644
--- a/frc971/zeroing/pot_and_index.cc
+++ b/frc971/zeroing/pot_and_index.cc
@@ -4,8 +4,7 @@
#include "glog/logging.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
PotAndIndexPulseZeroingEstimator::PotAndIndexPulseZeroingEstimator(
const constants::PotAndIndexPulseZeroingConstants &constants)
@@ -131,5 +130,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/pot_and_index_test.cc b/frc971/zeroing/pot_and_index_test.cc
index f2e464f..ef90661 100644
--- a/frc971/zeroing/pot_and_index_test.cc
+++ b/frc971/zeroing/pot_and_index_test.cc
@@ -4,9 +4,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::PotAndIndexPulseZeroingConstants;
@@ -278,6 +276,4 @@
ASSERT_TRUE(estimator.error());
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/pulse_index.cc b/frc971/zeroing/pulse_index.cc
index c0831e8..6e9a502 100644
--- a/frc971/zeroing/pulse_index.cc
+++ b/frc971/zeroing/pulse_index.cc
@@ -5,8 +5,7 @@
#include "glog/logging.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
void PulseIndexZeroingEstimator::Reset() {
max_index_position_ = ::std::numeric_limits<double>::lowest();
@@ -112,5 +111,4 @@
return builder.Finish();
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/pulse_index_test.cc b/frc971/zeroing/pulse_index_test.cc
index bd257f7..c07644d 100644
--- a/frc971/zeroing/pulse_index_test.cc
+++ b/frc971/zeroing/pulse_index_test.cc
@@ -4,9 +4,7 @@
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using constants::EncoderPlusIndexZeroingConstants;
@@ -127,6 +125,4 @@
}
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/relative_encoder_test.cc b/frc971/zeroing/relative_encoder_test.cc
index 6256fe7..28fe978 100644
--- a/frc971/zeroing/relative_encoder_test.cc
+++ b/frc971/zeroing/relative_encoder_test.cc
@@ -3,9 +3,7 @@
#include "frc971/zeroing/zeroing.h"
#include "frc971/zeroing/zeroing_test.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
class RelativeEncoderZeroingTest : public ZeroingTest {
protected:
@@ -35,6 +33,4 @@
EXPECT_DOUBLE_EQ(GetEstimatorPosition(&estimator), 0.1);
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/unwrap_test.cc b/frc971/zeroing/unwrap_test.cc
index b71c8b6..0a185b1 100644
--- a/frc971/zeroing/unwrap_test.cc
+++ b/frc971/zeroing/unwrap_test.cc
@@ -2,9 +2,7 @@
#include "frc971/zeroing/wrap.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
TEST(SensorTest, UnwrapOnce) {
// Test the sensor moving over the maximum range value and wrapping once
@@ -63,6 +61,4 @@
EXPECT_EQ(sensor.Unwrap(0.2), 0.2); // move = 1.0, wrap -1
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/frc971/zeroing/wrap.cc b/frc971/zeroing/wrap.cc
index 1a0504f..2e0e3bc 100644
--- a/frc971/zeroing/wrap.cc
+++ b/frc971/zeroing/wrap.cc
@@ -2,8 +2,7 @@
#include <cmath>
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
UnwrapSensor::UnwrapSensor(double sensor_offset, double sensor_range)
: sensor_offset_(sensor_offset), sensor_range_(sensor_range) {
@@ -64,5 +63,4 @@
return remainder(value - nearest, period) + nearest;
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
diff --git a/frc971/zeroing/wrap.h b/frc971/zeroing/wrap.h
index f96b9fb..1d10d58 100644
--- a/frc971/zeroing/wrap.h
+++ b/frc971/zeroing/wrap.h
@@ -1,8 +1,7 @@
#ifndef FRC971_ZEROING_WRAP_H_
#define FRC971_ZEROING_WRAP_H_
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// UnwrapSensor takes in a sensor value from a sensor that loops in a certain
// interval. ex(the sensor moves from 0 to 10 and back to 0 while moving the
@@ -50,7 +49,6 @@
return Wrap(nearest, value, period);
}
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_WRAP_H_
diff --git a/frc971/zeroing/wrap_test.cc b/frc971/zeroing/wrap_test.cc
index 6597e03..b5d990b 100644
--- a/frc971/zeroing/wrap_test.cc
+++ b/frc971/zeroing/wrap_test.cc
@@ -4,9 +4,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
// Tests some various positive and negative values for wrap.
TEST(WrapTest, TestWrap) {
@@ -52,6 +50,4 @@
EXPECT_NEAR(1.0f, Wrap(5.0f, -9.0f, 10.0f), 1e-6f);
}
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing