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/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