Nest some more namespaces
Did someone previously suggest that all namespace had been
nested? Silly.
Signed-off-by: Stephan Pleines <pleines.stephan@gmail.com>
Change-Id: I22278c1caaeba8b47dc46fb2ed3078c20a11e190
diff --git a/frc971/analysis/in_process_plotter.h b/frc971/analysis/in_process_plotter.h
index 6dab308..df81041 100644
--- a/frc971/analysis/in_process_plotter.h
+++ b/frc971/analysis/in_process_plotter.h
@@ -7,8 +7,7 @@
#include "aos/network/web_proxy.h"
#include "frc971/analysis/plot_data_generated.h"
-namespace frc971 {
-namespace analysis {
+namespace frc971::analysis {
// This class wraps the WebProxy class to provide a convenient C++ interface to
// dynamically generate plots.
@@ -96,6 +95,5 @@
std::vector<ColorWheelColor> color_wheel_;
};
-} // namespace analysis
-} // namespace frc971
+} // namespace frc971::analysis
#endif // FRC971_ANALYSIS_IN_PROCESS_PLOTTER_H_
diff --git a/frc971/autonomous/base_autonomous_actor.h b/frc971/autonomous/base_autonomous_actor.h
index 403854f..15c88d4 100644
--- a/frc971/autonomous/base_autonomous_actor.h
+++ b/frc971/autonomous/base_autonomous_actor.h
@@ -13,8 +13,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
class BaseAutonomousActor : public ::aos::common::actions::ActorBase<Goal> {
public:
@@ -156,7 +155,6 @@
int32_t goal_spline_handle_ = 0;
};
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
#endif // FRC971_AUTONOMOUS_BASE_AUTONOMOUS_ACTOR_H_
diff --git a/frc971/autonomous/user_button_localized_autonomous_actor.cc b/frc971/autonomous/user_button_localized_autonomous_actor.cc
index 5358a28..21fb42a 100644
--- a/frc971/autonomous/user_button_localized_autonomous_actor.cc
+++ b/frc971/autonomous/user_button_localized_autonomous_actor.cc
@@ -5,8 +5,7 @@
namespace this_thread = ::std::this_thread;
namespace drivetrain = frc971::control_loops::drivetrain;
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
UserButtonLocalizedAutonomousActor::UserButtonLocalizedAutonomousActor(
::aos::EventLoop *event_loop,
@@ -109,5 +108,4 @@
return Run(params);
}
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
diff --git a/frc971/autonomous/user_button_localized_autonomous_actor.h b/frc971/autonomous/user_button_localized_autonomous_actor.h
index 07d083a..3f6503d 100644
--- a/frc971/autonomous/user_button_localized_autonomous_actor.h
+++ b/frc971/autonomous/user_button_localized_autonomous_actor.h
@@ -14,8 +14,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
class UserButtonLocalizedAutonomousActor : public BaseAutonomousActor {
public:
@@ -54,7 +53,6 @@
bool user_indicated_safe_to_reset_ = false;
};
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
#endif // FRC971_AUTONOMOUS_EXTENDED_AUTONOMOUS_ACTOR_H_
diff --git a/frc971/can_logger/asc_logger.h b/frc971/can_logger/asc_logger.h
index 19a1cb9..2be2eb2 100644
--- a/frc971/can_logger/asc_logger.h
+++ b/frc971/can_logger/asc_logger.h
@@ -10,8 +10,7 @@
#include "aos/events/event_loop.h"
#include "frc971/can_logger/can_logging_generated.h"
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
class AscLogger {
public:
@@ -33,7 +32,6 @@
aos::EventLoop *event_loop_;
};
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
#endif // FRC971_CAN_LOGGER_ASC_LOGGER_H_
diff --git a/frc971/can_logger/can_logger.h b/frc971/can_logger/can_logger.h
index 432bac8..a144265 100644
--- a/frc971/can_logger/can_logger.h
+++ b/frc971/can_logger/can_logger.h
@@ -16,8 +16,7 @@
#include "aos/scoped/scoped_fd.h"
#include "frc971/can_logger/can_logging_generated.h"
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
// This class listens to all the traffic on a SocketCAN interface and sends it
// on the aos event loop so it can be logged with the aos logging
@@ -45,7 +44,6 @@
aos::Sender<CanFrame> frames_sender_;
};
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
#endif // FRC971_CAN_LOGGER_CAN_LOGGER_H_
diff --git a/frc971/codelab/basic.h b/frc971/codelab/basic.h
index 3aac567..6439d84 100644
--- a/frc971/codelab/basic.h
+++ b/frc971/codelab/basic.h
@@ -8,8 +8,7 @@
#include "frc971/codelab/basic_status_generated.h"
#include "frc971/control_loops/control_loop.h"
-namespace frc971 {
-namespace codelab {
+namespace frc971::codelab {
class Basic
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -23,7 +22,6 @@
aos::Sender<Status>::Builder *status) override;
};
-} // namespace codelab
-} // namespace frc971
+} // namespace frc971::codelab
#endif // FRC971_CODELAB_BASIC_H_
diff --git a/frc971/control_loops/c2d.h b/frc971/control_loops/c2d.h
index 7c1bf81..f80f88f 100644
--- a/frc971/control_loops/c2d.h
+++ b/frc971/control_loops/c2d.h
@@ -9,8 +9,7 @@
// We need to include MatrixFunctions for the matrix exponential.
#include "unsupported/Eigen/MatrixFunctions"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
template <typename Scalar, int num_states, int num_inputs>
void C2D(const ::Eigen::Matrix<Scalar, num_states, num_states> &A_continuous,
@@ -116,7 +115,6 @@
*A_d = phi22t;
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // FRC971_CONTROL_LOOPS_C2D_H_
diff --git a/frc971/control_loops/capped_test_plant.h b/frc971/control_loops/capped_test_plant.h
index 8b4cefd..4171719 100644
--- a/frc971/control_loops/capped_test_plant.h
+++ b/frc971/control_loops/capped_test_plant.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Basic state feedback plant for use in tests.
class CappedTestPlant : public StateFeedbackPlant<2, 1, 1> {
@@ -28,6 +27,5 @@
double voltage_offset_ = 0.0;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_CAPPED_TEST_PLANT_H_
diff --git a/frc971/control_loops/coerce_goal.h b/frc971/control_loops/coerce_goal.h
index 6867540..3d34e94 100644
--- a/frc971/control_loops/coerce_goal.h
+++ b/frc971/control_loops/coerce_goal.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/polytope.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
template <typename Scalar = double>
Eigen::Matrix<Scalar, 2, 1> DoCoerceGoal(
@@ -127,7 +126,6 @@
}
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_COERCE_GOAL_H_
diff --git a/frc971/control_loops/control_loop-tmpl.h b/frc971/control_loops/control_loop-tmpl.h
index 7e20227..d86c97c 100644
--- a/frc971/control_loops/control_loop-tmpl.h
+++ b/frc971/control_loops/control_loop-tmpl.h
@@ -3,8 +3,7 @@
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// TODO(aschuh): Tests.
@@ -91,5 +90,4 @@
status.CheckSent();
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
diff --git a/frc971/control_loops/control_loop.h b/frc971/control_loops/control_loop.h
index c02d094..500c81c 100644
--- a/frc971/control_loops/control_loop.h
+++ b/frc971/control_loops/control_loop.h
@@ -10,8 +10,7 @@
#include "frc971/input/joystick_state_generated.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// Control loops run this often, "starting" at time 0.
constexpr ::std::chrono::nanoseconds kLoopFrequency =
@@ -132,8 +131,7 @@
SimpleLogInterval(kStaleLogInterval, ERROR, "no goal");
};
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#include "frc971/control_loops/control_loop-tmpl.h" // IWYU pragma: export
diff --git a/frc971/control_loops/control_loop_test.h b/frc971/control_loops/control_loop_test.h
index 00062b9..8b6ba09 100644
--- a/frc971/control_loops/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -16,8 +16,7 @@
#include "frc971/input/joystick_state_generated.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace testing {
+namespace frc971::testing {
// Handles setting up the environment that all control loops need to actually
// run.
@@ -219,7 +218,6 @@
constexpr ::std::chrono::milliseconds
ControlLoopTestTemplated<TestBaseClass>::kDSPacketTime;
-} // namespace testing
-} // namespace frc971
+} // namespace frc971::testing
#endif // AOS_CONTROLS_CONTROL_LOOP_TEST_H_
diff --git a/frc971/control_loops/dlqr.h b/frc971/control_loops/dlqr.h
index 48e8474..57aa88b 100644
--- a/frc971/control_loops/dlqr.h
+++ b/frc971/control_loops/dlqr.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
template <int num_states, int num_inputs>
int Controllability(const ::Eigen::Matrix<double, num_states, num_states> &A,
@@ -114,7 +113,6 @@
return INFO;
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // FRC971_CONTROL_LOOPS_DLQR_H_
diff --git a/frc971/control_loops/double_jointed_arm/demo_path.h b/frc971/control_loops/double_jointed_arm/demo_path.h
index 9a9d393..691258b 100644
--- a/frc971/control_loops/double_jointed_arm/demo_path.h
+++ b/frc971/control_loops/double_jointed_arm/demo_path.h
@@ -5,15 +5,11 @@
#include "frc971/control_loops/double_jointed_arm/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
::std::unique_ptr<Path> MakeDemoPath();
::std::unique_ptr<Path> MakeReversedDemoPath();
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DEMO_PATH_H_
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.h b/frc971/control_loops/double_jointed_arm/dynamics.h
index c6b078b..c28a20d 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics.h
+++ b/frc971/control_loops/double_jointed_arm/dynamics.h
@@ -8,9 +8,7 @@
DECLARE_bool(gravity);
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
struct ArmConstants {
// Below, 0 refers to the proximal joint, and 1 refers to the distal joint.
@@ -242,8 +240,6 @@
const double gamma_;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
diff --git a/frc971/control_loops/double_jointed_arm/ekf.h b/frc971/control_loops/double_jointed_arm/ekf.h
index 45e1641..f815807 100644
--- a/frc971/control_loops/double_jointed_arm/ekf.h
+++ b/frc971/control_loops/double_jointed_arm/ekf.h
@@ -5,9 +5,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// An extended kalman filter for the Arm.
// Our states are:
@@ -48,8 +46,6 @@
const Dynamics *dynamics_;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_EKF_H_
diff --git a/frc971/control_loops/double_jointed_arm/graph.h b/frc971/control_loops/double_jointed_arm/graph.h
index 06d396c..c1c09ef 100644
--- a/frc971/control_loops/double_jointed_arm/graph.h
+++ b/frc971/control_loops/double_jointed_arm/graph.h
@@ -8,9 +8,7 @@
#include <memory>
#include <vector>
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// Grr... normal priority queues don't allow modifying the node cost.
// This relies on pointer stability for the passed in T.
@@ -181,8 +179,6 @@
size_t last_searched_vertex_ = std::numeric_limits<size_t>::max();
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_GRAPH_H_
diff --git a/frc971/control_loops/double_jointed_arm/test_constants.h b/frc971/control_loops/double_jointed_arm/test_constants.h
index 4ca2293..d71717d 100644
--- a/frc971/control_loops/double_jointed_arm/test_constants.h
+++ b/frc971/control_loops/double_jointed_arm/test_constants.h
@@ -3,10 +3,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
-namespace testing {
+namespace frc971::control_loops::arm::testing {
constexpr double kEfficiencyTweak = 0.95;
constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
@@ -44,9 +41,6 @@
.num_distal_motors = 2.0,
};
-} // namespace testing
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm::testing
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TEST_CONSTANTS_H_
diff --git a/frc971/control_loops/double_jointed_arm/trajectory.h b/frc971/control_loops/double_jointed_arm/trajectory.h
index ca570d2..82cf2a7 100644
--- a/frc971/control_loops/double_jointed_arm/trajectory.h
+++ b/frc971/control_loops/double_jointed_arm/trajectory.h
@@ -10,9 +10,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// This class represents a path in theta0, theta1 space. It also returns the
// position, velocity and acceleration of the path as a function of path
@@ -439,8 +437,6 @@
int failed_solutions_ = 0;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TRAJECTORY_H_
diff --git a/frc971/control_loops/drivetrain/camera.h b/frc971/control_loops/drivetrain/camera.h
index e1d4b76..6e87357 100644
--- a/frc971/control_loops/drivetrain/camera.h
+++ b/frc971/control_loops/drivetrain/camera.h
@@ -6,8 +6,7 @@
#include "aos/containers/sized_array.h"
#include "frc971/control_loops/pose.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Represents a target on the field. Currently just consists of a pose and a
// indicator for whether it is occluded (occlusion is only used by the simulator
@@ -366,7 +365,6 @@
views->push_back(view);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_CAMERA_H_
diff --git a/frc971/control_loops/drivetrain/distance_spline.h b/frc971/control_loops/drivetrain/distance_spline.h
index 63156fe..5c404a0 100644
--- a/frc971/control_loops/drivetrain/distance_spline.h
+++ b/frc971/control_loops/drivetrain/distance_spline.h
@@ -11,9 +11,7 @@
#include "frc971/control_loops/drivetrain/trajectory_generated.h"
#include "frc971/control_loops/fixed_quadrature.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
std::vector<Spline> FlatbufferToSplines(const MultiSpline *fb);
@@ -127,8 +125,6 @@
absl::Span<const float> distances_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DISTANCE_SPLINE_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index c92b7d7..87266f1 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -25,9 +25,7 @@
#include "frc971/wpilib/imu_batch_generated.h"
#include "frc971/zeroing/imu_zeroer.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace chrono = std::chrono;
@@ -195,8 +193,6 @@
aos::SendFailureCounter status_failure_counter_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.h b/frc971/control_loops/drivetrain/drivetrain_config.h
index 31c911a..8e0a58d 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.h
+++ b/frc971/control_loops/drivetrain/drivetrain_config.h
@@ -13,9 +13,7 @@
#include "frc971/control_loops/state_feedback_loop_converters.h"
#include "frc971/shifter_hall_effect.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Configuration for line-following mode.
struct LineFollowConfig {
@@ -236,8 +234,6 @@
};
}
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.h b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
index 4368b00..a79ba72 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.h
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
@@ -15,10 +15,7 @@
#include "frc971/queues/gyro_generated.h"
#include "frc971/wpilib/imu_batch_generated.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
const DrivetrainConfig<double> &GetTestDrivetrainConfig();
@@ -174,9 +171,6 @@
double accel_sin_wave_magnitude_ = 0.0;
};
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_TEST_LIB_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_uc.q.h b/frc971/control_loops/drivetrain/drivetrain_uc.q.h
index 95a2000..5b0bb83 100644
--- a/frc971/control_loops/drivetrain/drivetrain_uc.q.h
+++ b/frc971/control_loops/drivetrain/drivetrain_uc.q.h
@@ -4,8 +4,7 @@
#include "aos/macros.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
struct GearLogging {
GearLogging();
@@ -111,7 +110,6 @@
DrivetrainQueue_Status status;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_Q_H_
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf.h b/frc971/control_loops/drivetrain/hybrid_ekf.h
index 743e494..f784f2e 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf.h
+++ b/frc971/control_loops/drivetrain/hybrid_ekf.h
@@ -12,17 +12,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace y2019 {
-namespace control_loops {
-namespace testing {
+namespace y2019::control_loops::testing {
class ParameterizedLocalizerTest;
-} // namespace testing
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::testing
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace testing {
class HybridEkfTest;
@@ -934,8 +928,6 @@
P_.setZero();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator.h b/frc971/control_loops/drivetrain/improved_down_estimator.h
index b5cc509..c778ad5 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator.h
+++ b/frc971/control_loops/drivetrain/improved_down_estimator.h
@@ -12,9 +12,7 @@
#include "frc971/control_loops/quaternion_utils.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Generates the sigma points to use in the UKF given the current estimate and
// covariance.
@@ -256,8 +254,6 @@
aos::monotonic_clock::time_point now);
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_IMPROVED_DOWN_ESTIMATOR_H_
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.h b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
index bb2f7ae..245d0e9 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.h
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
@@ -12,9 +12,7 @@
#include "frc971/control_loops/profiled_subsystem_generated.h"
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace testing {
class LineFollowDrivetrainTest;
@@ -93,8 +91,6 @@
friend class testing::LineFollowDrivetrainTest;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_LINE_FOLLOW_DRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer.h b/frc971/control_loops/drivetrain/localization/puppet_localizer.h
index 9b348a7..a3ebe1d 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer.h
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer.h
@@ -9,9 +9,7 @@
#include "frc971/control_loops/drivetrain/localization/localizer_output_generated.h"
#include "frc971/control_loops/drivetrain/localizer.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// This class handles the localization for the 2022/2023 robots. Rather than
// actually doing any work on the roborio, we farm all the localization out to a
@@ -104,8 +102,6 @@
target_selector_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_LOCALIZATION_PUPPET_LOCALIZER_H_
diff --git a/frc971/control_loops/drivetrain/localizer.h b/frc971/control_loops/drivetrain/localizer.h
index 867b3c0..6f5bf3d 100644
--- a/frc971/control_loops/drivetrain/localizer.h
+++ b/frc971/control_loops/drivetrain/localizer.h
@@ -7,9 +7,7 @@
#include "frc971/control_loops/drivetrain/hybrid_ekf.h"
#include "frc971/control_loops/pose.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// An interface for target selection. This provides an object that will take in
// state updates and then determine what poes we should be driving to.
@@ -214,8 +212,6 @@
TrivialTargetSelector target_selector_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_FIELD_ESTIMATOR_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.h b/frc971/control_loops/drivetrain/polydrivetrain.h
index a9dea7e..f4c608d 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.h
+++ b/frc971/control_loops/drivetrain/polydrivetrain.h
@@ -23,9 +23,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_states.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
template <typename Scalar = double>
class PolyDrivetrain {
@@ -457,8 +455,6 @@
return builder.Finish();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/spline.h b/frc971/control_loops/drivetrain/spline.h
index 2c000bf..af42040 100644
--- a/frc971/control_loops/drivetrain/spline.h
+++ b/frc971/control_loops/drivetrain/spline.h
@@ -5,9 +5,7 @@
#include "frc971/control_loops/binomial.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Class to hold a spline as a function of alpha. Alpha can only range between
// 0.0 and 1.0.
@@ -190,8 +188,6 @@
return ans;
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SPLINE_H_
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.h b/frc971/control_loops/drivetrain/splinedrivetrain.h
index c528733..f02a5b6 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.h
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.h
@@ -17,9 +17,7 @@
#include "frc971/control_loops/drivetrain/spline.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
class SplineDrivetrain {
public:
@@ -111,8 +109,6 @@
bool output_was_capped_ = false;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SPLINEDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/ssdrivetrain.h b/frc971/control_loops/drivetrain/ssdrivetrain.h
index 77f1e25..7059f15 100644
--- a/frc971/control_loops/drivetrain/ssdrivetrain.h
+++ b/frc971/control_loops/drivetrain/ssdrivetrain.h
@@ -15,9 +15,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 {
class DrivetrainMotorsSS {
public:
@@ -70,8 +68,6 @@
LocalizerInterface *localizer_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SSDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/trajectory.h b/frc971/control_loops/drivetrain/trajectory.h
index b2cecc0..a9f14f6 100644
--- a/frc971/control_loops/drivetrain/trajectory.h
+++ b/frc971/control_loops/drivetrain/trajectory.h
@@ -14,9 +14,7 @@
#include "frc971/control_loops/runge_kutta.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
template <typename F>
double IntegrateAccelForDistance(const F &fn, double v, double x, double dx) {
@@ -423,8 +421,6 @@
.finished();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_H_
diff --git a/frc971/control_loops/drivetrain/trajectory_generator.h b/frc971/control_loops/drivetrain/trajectory_generator.h
index 234d386..5d638d3 100644
--- a/frc971/control_loops/drivetrain/trajectory_generator.h
+++ b/frc971/control_loops/drivetrain/trajectory_generator.h
@@ -6,9 +6,7 @@
#include "frc971/control_loops/drivetrain/spline_goal_generated.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
class TrajectoryGenerator {
public:
@@ -22,8 +20,6 @@
aos::Sender<fb::Trajectory> trajectory_sender_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_GENERATOR_H_
diff --git a/frc971/control_loops/fixed_quadrature.h b/frc971/control_loops/fixed_quadrature.h
index 53bb0dc..88d52e8 100644
--- a/frc971/control_loops/fixed_quadrature.h
+++ b/frc971/control_loops/fixed_quadrature.h
@@ -5,8 +5,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Implements Gaussian Quadrature integration (5th order). fn is the function
// to integrate. It must take 1 argument of type T. The integration is between
@@ -57,7 +56,6 @@
return answer;
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_FIXED_QUADRATURE_H_
diff --git a/frc971/control_loops/flywheel/flywheel_controller.h b/frc971/control_loops/flywheel/flywheel_controller.h
index db8baeb..49a4385 100644
--- a/frc971/control_loops/flywheel/flywheel_controller.h
+++ b/frc971/control_loops/flywheel/flywheel_controller.h
@@ -9,9 +9,7 @@
#include "frc971/control_loops/hybrid_state_feedback_loop.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
+namespace frc971::control_loops::flywheel {
class CurrentLimitedStateFeedbackController;
@@ -73,8 +71,6 @@
DISALLOW_COPY_AND_ASSIGN(FlywheelController);
};
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel
#endif // FRC971_CONTROL_LOOPS_SHOOTER_FLYWHEEL_CONTROLLER_H_
diff --git a/frc971/control_loops/flywheel/flywheel_controller_test.cc b/frc971/control_loops/flywheel/flywheel_controller_test.cc
index 26aabc9..eaac6e6 100644
--- a/frc971/control_loops/flywheel/flywheel_controller_test.cc
+++ b/frc971/control_loops/flywheel/flywheel_controller_test.cc
@@ -9,10 +9,7 @@
#include "frc971/control_loops/flywheel/flywheel_test_plant.h"
#include "frc971/control_loops/flywheel/integral_flywheel_controller_test_plant.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
-namespace testing {
+namespace frc971::control_loops::flywheel::testing {
class FlywheelTest : public ::frc971::testing::ControlLoopTest {
public:
FlywheelTest()
@@ -97,7 +94,4 @@
RunFor(std::chrono::seconds(8));
VerifyNearGoal();
}
-} // namespace testing
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel::testing
diff --git a/frc971/control_loops/flywheel/flywheel_test_plant.h b/frc971/control_loops/flywheel/flywheel_test_plant.h
index 01e347d..269e147 100644
--- a/frc971/control_loops/flywheel/flywheel_test_plant.h
+++ b/frc971/control_loops/flywheel/flywheel_test_plant.h
@@ -3,9 +3,7 @@
#include "frc971/control_loops/flywheel/flywheel_controller.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
+namespace frc971::control_loops::flywheel {
class FlywheelPlant : public StateFeedbackPlant<2, 1, 1> {
public:
@@ -40,8 +38,6 @@
double resistance_;
};
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel
#endif // FRC971_CONTROL_LOOPS_FLYWHEEL_FLYWHEEL_TEST_PLANT_H_
diff --git a/frc971/control_loops/gaussian_noise.h b/frc971/control_loops/gaussian_noise.h
index dce60fb..a784df0 100644
--- a/frc971/control_loops/gaussian_noise.h
+++ b/frc971/control_loops/gaussian_noise.h
@@ -6,8 +6,7 @@
#include <memory>
#include <random>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
class GaussianNoise {
public:
@@ -28,7 +27,6 @@
std::normal_distribution<double> distribution_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_GAUSSIAN_NOISE_H_
diff --git a/frc971/control_loops/jacobian.h b/frc971/control_loops/jacobian.h
index 0940c6c..5442ec8 100644
--- a/frc971/control_loops/jacobian.h
+++ b/frc971/control_loops/jacobian.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
template <int num_states, int num_inputs, typename F>
::Eigen::Matrix<double, num_states, num_inputs> NumericalJacobian(
@@ -46,7 +45,6 @@
U);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_JACOBIAN_H_
diff --git a/frc971/control_loops/polytope.h b/frc971/control_loops/polytope.h
index 794219b..cba25f6 100644
--- a/frc971/control_loops/polytope.h
+++ b/frc971/control_loops/polytope.h
@@ -14,8 +14,7 @@
#include "glog/logging.h"
#endif // __linux__
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// A number_of_dimensions dimensional polytope.
// This represents the region consisting of all points X such that H * X <= k.
@@ -238,7 +237,6 @@
}
#endif // __linux__
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // AOS_CONTROLS_POLYTOPE_H_
diff --git a/frc971/control_loops/pose.h b/frc971/control_loops/pose.h
index 1eccf28..6570e9c 100644
--- a/frc971/control_loops/pose.h
+++ b/frc971/control_loops/pose.h
@@ -7,8 +7,7 @@
#include "aos/util/math.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Constructs a homogeneous transformation matrix for rotating about the Z axis.
template <typename Scalar>
@@ -231,7 +230,6 @@
typedef TypedLineSegment<double> LineSegment;
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_POSE_H_
diff --git a/frc971/control_loops/position_sensor_sim.h b/frc971/control_loops/position_sensor_sim.h
index fae0e7d..a2d765e 100644
--- a/frc971/control_loops/position_sensor_sim.h
+++ b/frc971/control_loops/position_sensor_sim.h
@@ -7,8 +7,7 @@
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/gaussian_noise.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// NOTE: All potentiometer and encoder values in this class are assumed to be in
// translated SI units.
@@ -211,7 +210,6 @@
double negedge_value_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif /* FRC971_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_ */
diff --git a/frc971/control_loops/profiled_subsystem.h b/frc971/control_loops/profiled_subsystem.h
index 2a15201..7a0b7fa 100644
--- a/frc971/control_loops/profiled_subsystem.h
+++ b/frc971/control_loops/profiled_subsystem.h
@@ -18,8 +18,7 @@
#include "frc971/zeroing/pot_and_index.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// TODO(Brian): Use a tuple instead of an array to support heterogeneous zeroing
// styles.
@@ -466,7 +465,6 @@
internal::UseUnlessZero(max_angular_acceleration, default_acceleration_));
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_PROFILED_SUBSYSTEM_H_
diff --git a/frc971/control_loops/quaternion_utils.h b/frc971/control_loops/quaternion_utils.h
index e97935c..e96f5f1 100644
--- a/frc971/control_loops/quaternion_utils.h
+++ b/frc971/control_loops/quaternion_utils.h
@@ -5,8 +5,7 @@
#include "Eigen/Geometry"
#include "glog/logging.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// Function to compute the quaternion average of a bunch of quaternions. Each
// column in the input matrix is a quaternion (optionally scaled by it's
@@ -93,7 +92,6 @@
return QuaternionDerivativeDerivitive(q.coeffs());
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // AOS_CONTROLS_QUATERNION_UTILS_H_
diff --git a/frc971/control_loops/runge_kutta.h b/frc971/control_loops/runge_kutta.h
index 7fa3f3e..ed5a359 100644
--- a/frc971/control_loops/runge_kutta.h
+++ b/frc971/control_loops/runge_kutta.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Implements Runge Kutta integration (4th order). fn is the function to
// integrate. It must take 1 argument of type T. The integration starts at an
@@ -67,7 +66,6 @@
return X + dt / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_RUNGE_KUTTA_H_
diff --git a/frc971/control_loops/simple_capped_state_feedback_loop.h b/frc971/control_loops/simple_capped_state_feedback_loop.h
index b2049a6..c159e15 100644
--- a/frc971/control_loops/simple_capped_state_feedback_loop.h
+++ b/frc971/control_loops/simple_capped_state_feedback_loop.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// A StateFeedbackLoop which implements CapU based on a simple set of maximum
// absolute values for each element of U.
@@ -74,7 +73,6 @@
::Eigen::Array<double, number_of_inputs, 1> max_voltages_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_SIMPLE_CAPPED_STATE_FEEDBACK_LOOP_H_
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
index b26f69c..82017a4 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/profiled_subsystem.h"
#include "frc971/control_loops/state_feedback_loop_converters.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
template <typename ZeroingEstimator>
struct StaticZeroingSingleDOFProfiledSubsystemParams {
@@ -426,7 +425,6 @@
return status_builder.Finish();
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_STATIC_ZEROING_SINGLE_DOF_PROFILED_SUBSYSTEM_H_
diff --git a/frc971/control_loops/team_number_test_environment.h b/frc971/control_loops/team_number_test_environment.h
index 5c95c28..6e7dea8 100644
--- a/frc971/control_loops/team_number_test_environment.h
+++ b/frc971/control_loops/team_number_test_environment.h
@@ -3,9 +3,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// The team number we use for tests.
static const int kTeamNumber = 1;
@@ -23,8 +21,6 @@
__attribute__((unused)) static ::testing::Environment *const team_number_env =
::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment());
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
#endif // FRC971_CONTROL_LOOPS_TEAM_NUMBER_TEST_ENVIRONMENT_H_
diff --git a/frc971/control_loops/voltage_cap/voltage_cap.h b/frc971/control_loops/voltage_cap/voltage_cap.h
index ad4e4c6c..f30d5af 100644
--- a/frc971/control_loops/voltage_cap/voltage_cap.h
+++ b/frc971/control_loops/voltage_cap/voltage_cap.h
@@ -3,8 +3,7 @@
#include <cstdio>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// This function maintains the difference of power between two voltages passed
// in that are outside of our range of possible voltage output.
@@ -27,7 +26,6 @@
void VoltageCap(double voltage_one, double voltage_two, double *out_voltage_one,
double *out_voltage_two);
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_VOLTAGE_CAP_VOLTAGE_CAP_H_
diff --git a/frc971/input/action_joystick_input.h b/frc971/input/action_joystick_input.h
index f77f416..ac37c2a 100644
--- a/frc971/input/action_joystick_input.h
+++ b/frc971/input/action_joystick_input.h
@@ -8,8 +8,7 @@
#include "frc971/input/drivetrain_input.h"
#include "frc971/input/joystick_input.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
// Class to abstract out managing actions, autonomous mode, and drivetrains.
// Turns out we do the same thing every year, so let's stop copying it.
@@ -139,7 +138,6 @@
::aos::Fetcher<::frc971::autonomous::AutonomousMode> autonomous_mode_fetcher_;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_ACTION_JOYSTICK_INPUT_H_
diff --git a/frc971/input/driver_station_data.h b/frc971/input/driver_station_data.h
index 5ebf8f4..7d8dc3e 100644
--- a/frc971/input/driver_station_data.h
+++ b/frc971/input/driver_station_data.h
@@ -9,9 +9,7 @@
#include "frc971/input/joystick_state_generated.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
// Represents a feature of a joystick (a button or an axis).
// All indices are 1-based.
@@ -126,8 +124,6 @@
SavedJoystickState current_values_, old_values_;
};
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
#endif // AOS_INPUT_DRIVER_STATION_DATA_H_
diff --git a/frc971/input/drivetrain_input.h b/frc971/input/drivetrain_input.h
index 0cb724d..173c551 100644
--- a/frc971/input/drivetrain_input.h
+++ b/frc971/input/drivetrain_input.h
@@ -13,8 +13,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
using control_loops::drivetrain::PistolBottomButtonUse;
using control_loops::drivetrain::PistolSecondButtonUse;
@@ -271,7 +270,6 @@
const ::frc971::input::driver_station::Data &data) override;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_DRIVETRAIN_INPUT_H_
diff --git a/frc971/input/joystick_input.h b/frc971/input/joystick_input.h
index 074908d..b6d0ceb 100644
--- a/frc971/input/joystick_input.h
+++ b/frc971/input/joystick_input.h
@@ -6,8 +6,7 @@
#include "aos/events/event_loop.h"
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
// A class for handling joystick packet values.
// It will call RunIteration each time a new packet is received.
@@ -40,7 +39,6 @@
int mode_;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_JOYSTICK_INPUT_H_
diff --git a/frc971/input/redundant_joystick_data.h b/frc971/input/redundant_joystick_data.h
index c6cdb78..56fc6b5 100644
--- a/frc971/input/redundant_joystick_data.h
+++ b/frc971/input/redundant_joystick_data.h
@@ -3,9 +3,7 @@
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
// A class to wrap driver_station::Data and map logical joystick numbers to
// their actual numbers in the order they are on the driverstation.
@@ -51,8 +49,6 @@
const Data &data_;
};
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
#endif // AOS_INPUT_REDUNDANT_JOYSTICK_DATA_H_
diff --git a/frc971/orin/apriltag.h b/frc971/orin/apriltag.h
index f87e107..d3e041b 100644
--- a/frc971/orin/apriltag.h
+++ b/frc971/orin/apriltag.h
@@ -12,8 +12,7 @@
#include "frc971/orin/line_fit_filter.h"
#include "frc971/orin/points.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to find the blob index of a point in a point vector.
class BlobExtentsIndexFinder {
@@ -326,7 +325,6 @@
zarray_t *detections_ = nullptr;
};
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_APRILTAG_H_
diff --git a/frc971/orin/cuda.h b/frc971/orin/cuda.h
index 2cc8f44..0e44fb4 100644
--- a/frc971/orin/cuda.h
+++ b/frc971/orin/cuda.h
@@ -17,8 +17,7 @@
LOG(FATAL) << "Check failed: " #condition " (" << cudaGetErrorString(c) \
<< ") "
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to manage the lifetime of a Cuda stream. This is used to provide
// relative ordering between kernels on the same stream.
@@ -205,7 +204,6 @@
void MaybeCheckAndSynchronize();
void MaybeCheckAndSynchronize(std::string_view message);
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_CUDA_H_
diff --git a/frc971/orin/line_fit_filter.h b/frc971/orin/line_fit_filter.h
index 0c37f0b..7ecc553 100644
--- a/frc971/orin/line_fit_filter.h
+++ b/frc971/orin/line_fit_filter.h
@@ -8,8 +8,7 @@
#include "device_launch_parameters.h"
#include "frc971/orin/cuda.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to hold the extents of a blob of points.
struct MinMaxExtents {
@@ -160,7 +159,6 @@
// The max number of work elements for a max maxes of 10.
constexpr size_t MaxRankedIndex() { return 210; }
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_LINE_FIT_FILTER_H_
diff --git a/frc971/orin/points.h b/frc971/orin/points.h
index d530a17..745e151 100644
--- a/frc971/orin/points.h
+++ b/frc971/orin/points.h
@@ -11,8 +11,7 @@
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to hold the 2 adjacent blob IDs, a point in decimated image space, the
// half pixel offset, and the gradient.
@@ -297,7 +296,6 @@
}
};
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_POINTS_H_
diff --git a/frc971/orin/threshold.h b/frc971/orin/threshold.h
index 5cdc3a2..03eb59a 100644
--- a/frc971/orin/threshold.h
+++ b/frc971/orin/threshold.h
@@ -5,8 +5,7 @@
#include "frc971/orin/cuda.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Converts to grayscale, decimates, and thresholds an image on the provided
// stream.
@@ -16,7 +15,6 @@
uint8_t *thresholded_image, size_t width, size_t height,
size_t min_white_black_diff, CudaStream *stream);
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_THRESHOLD_H_
diff --git a/frc971/shooter_interpolation/interpolation.h b/frc971/shooter_interpolation/interpolation.h
index bce532f..26b141f 100644
--- a/frc971/shooter_interpolation/interpolation.h
+++ b/frc971/shooter_interpolation/interpolation.h
@@ -5,8 +5,7 @@
#include <utility>
#include <vector>
-namespace frc971 {
-namespace shooter_interpolation {
+namespace frc971::shooter_interpolation {
double Blend(double coefficient, double a1, double a2);
@@ -79,7 +78,6 @@
}
}
-} // namespace shooter_interpolation
-} // namespace frc971
+} // namespace frc971::shooter_interpolation
#endif // FRC971_SHOOTER_INTERPOLATION_INTERPOLATION_H_
diff --git a/frc971/solvers/convex.h b/frc971/solvers/convex.h
index 3de357c..d8989d8 100644
--- a/frc971/solvers/convex.h
+++ b/frc971/solvers/convex.h
@@ -10,8 +10,7 @@
#include "glog/logging.h"
#include <Eigen/Dense>
-namespace frc971 {
-namespace solvers {
+namespace frc971::solvers {
// TODO(austin): Steal JET from Ceres to generate the derivatives easily and
// quickly?
@@ -379,7 +378,6 @@
}
}
-}; // namespace solvers
-}; // namespace frc971
+} // namespace frc971::solvers
#endif // FRC971_SOLVERS_CONVEX_H_
diff --git a/frc971/solvers/sparse_convex.h b/frc971/solvers/sparse_convex.h
index 9695431..074f2f3 100644
--- a/frc971/solvers/sparse_convex.h
+++ b/frc971/solvers/sparse_convex.h
@@ -9,8 +9,7 @@
#include "glog/logging.h"
#include <Eigen/Sparse>
-namespace frc971 {
-namespace solvers {
+namespace frc971::solvers {
// TODO(austin): Steal JET from Ceres to generate the derivatives easily and
// quickly?
@@ -118,7 +117,6 @@
std::string_view prefix, int verbosity);
};
-} // namespace solvers
-} // namespace frc971
+} // namespace frc971::solvers
#endif // FRC971_SOLVERS_SPARSE_CONVEX_H_
diff --git a/frc971/vision/calibration_accumulator.h b/frc971/vision/calibration_accumulator.h
index 9a6f483..550b691 100644
--- a/frc971/vision/calibration_accumulator.h
+++ b/frc971/vision/calibration_accumulator.h
@@ -12,8 +12,7 @@
#include "frc971/vision/foxglove_image_converter_lib.h"
#include "frc971/wpilib/imu_batch_generated.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// This class provides an interface for an application to be notified of all
// camera and IMU samples in order with the correct timestamps.
@@ -143,7 +142,6 @@
frc971::IMUValuesT last_value_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_CALIBRATION_ACCUMULATOR_H_
diff --git a/frc971/vision/ceres/pose_graph_3d_error_term.h b/frc971/vision/ceres/pose_graph_3d_error_term.h
index 4dd5fbd..217b2a9 100644
--- a/frc971/vision/ceres/pose_graph_3d_error_term.h
+++ b/frc971/vision/ceres/pose_graph_3d_error_term.h
@@ -36,8 +36,7 @@
#include "types.h"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
// Computes the error term for two poses that have a relative pose measurement
// between them. Let the hat variables be the measurement. We have two poses x_a
@@ -133,7 +132,6 @@
const double weight_;
};
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_POSE_GRAPH_3D_ERROR_TERM_H_
diff --git a/frc971/vision/ceres/read_g2o.h b/frc971/vision/ceres/read_g2o.h
index 69fa16a..c427939 100644
--- a/frc971/vision/ceres/read_g2o.h
+++ b/frc971/vision/ceres/read_g2o.h
@@ -38,8 +38,7 @@
#include "glog/logging.h"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
// Reads a single pose from the input and inserts it into the map. Returns false
// if there is a duplicate entry.
@@ -136,7 +135,6 @@
return true;
}
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_READ_G2O_H_
diff --git a/frc971/vision/ceres/types.h b/frc971/vision/ceres/types.h
index 17e9bd3..9c1e495 100644
--- a/frc971/vision/ceres/types.h
+++ b/frc971/vision/ceres/types.h
@@ -39,8 +39,7 @@
#include "Eigen/Core"
#include "Eigen/Geometry"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
struct Pose3d {
Eigen::Vector3d p;
@@ -104,7 +103,6 @@
typedef std::vector<Constraint3d, Eigen::aligned_allocator<Constraint3d>>
VectorOfConstraints;
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_TYPES_H_
diff --git a/frc971/vision/charuco_lib.h b/frc971/vision/charuco_lib.h
index 62923db..aac25ee 100644
--- a/frc971/vision/charuco_lib.h
+++ b/frc971/vision/charuco_lib.h
@@ -17,8 +17,7 @@
DECLARE_bool(visualize);
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Class to find extrinsics for a specified pi's camera using the provided
// training data.
@@ -211,7 +210,6 @@
const foxglove::PointsAnnotationType line_type =
foxglove::PointsAnnotationType::POINTS);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_CHARUCO_LIB_H_
diff --git a/frc971/vision/extrinsics_calibration.h b/frc971/vision/extrinsics_calibration.h
index f6c3ccc..97d719f 100644
--- a/frc971/vision/extrinsics_calibration.h
+++ b/frc971/vision/extrinsics_calibration.h
@@ -6,8 +6,7 @@
#include "frc971/vision/calibration_accumulator.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
struct CalibrationParameters {
Eigen::Quaternion<double> initial_orientation =
@@ -55,7 +54,6 @@
void Visualize(const CalibrationData &data,
const CalibrationParameters &calibration_parameters);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_EXTRINSICS_CALIBRATION_H_
diff --git a/frc971/vision/intrinsics_calibration_lib.h b/frc971/vision/intrinsics_calibration_lib.h
index 3076ed9..7f08138 100644
--- a/frc971/vision/intrinsics_calibration_lib.h
+++ b/frc971/vision/intrinsics_calibration_lib.h
@@ -16,8 +16,7 @@
#include "aos/util/file.h"
#include "frc971/vision/charuco_lib.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
class IntrinsicsCalibration {
public:
@@ -76,6 +75,5 @@
aos::ExitHandle *exit_handle_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_CALIBRATION_LIB_H_
diff --git a/frc971/vision/media_device.h b/frc971/vision/media_device.h
index a2a86fe..31d0882 100644
--- a/frc971/vision/media_device.h
+++ b/frc971/vision/media_device.h
@@ -16,8 +16,7 @@
#include "aos/scoped/scoped_fd.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
class MediaDevice;
class Pad;
@@ -254,7 +253,6 @@
// nullopt otherwise.
std::optional<MediaDevice> FindMediaDevice(std::string_view device);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_MEDIA_DEVICE_H_
diff --git a/frc971/vision/v4l2_reader.h b/frc971/vision/v4l2_reader.h
index 6338ba5..a3d6252 100644
--- a/frc971/vision/v4l2_reader.h
+++ b/frc971/vision/v4l2_reader.h
@@ -16,8 +16,7 @@
#include "aos/util/threaded_consumer.h"
#include "frc971/vision/vision_generated.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Reads images from a V4L2 capture device (aka camera).
class V4L2ReaderBase {
@@ -199,7 +198,6 @@
aos::util::ThreadedConsumer<int, kNumberBuffers> buffer_requeuer_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_V4L2_READER_H_
diff --git a/frc971/vision/visualize_robot.h b/frc971/vision/visualize_robot.h
index c679dba..af2dcef 100644
--- a/frc971/vision/visualize_robot.h
+++ b/frc971/vision/visualize_robot.h
@@ -7,8 +7,7 @@
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Helper class to visualize the coordinate frames associated with
// the robot Based on a virtual camera viewpoint, and camera model,
@@ -80,7 +79,6 @@
// DrawFrameAxes
cv::Size default_size_; // Default image size
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_VISUALIZE_ROBOT_H_
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 6d5eb28..ed8e091 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -17,8 +17,7 @@
#include "frc971/wpilib/imu_generated.h"
#include "frc971/wpilib/spi_rx_clearer.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles interfacing with an Analog Devices ADIS16448 Inertial Sensor over
// SPI and sending values out on a queue.
@@ -100,7 +99,6 @@
FpgaTimeConverter time_converter_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_ADIS16448_H_
diff --git a/frc971/wpilib/ADIS16470.h b/frc971/wpilib/ADIS16470.h
index 35bcb06..c15ca5b 100644
--- a/frc971/wpilib/ADIS16470.h
+++ b/frc971/wpilib/ADIS16470.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/imu_batch_generated.h"
#include "frc971/wpilib/imu_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles interfacing with an Analog Devices ADIS16470 over SPI and sending the
// resulting values out on a channel.
@@ -93,7 +92,6 @@
FpgaTimeConverter time_converter_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_ADIS16470_H_
diff --git a/frc971/wpilib/buffered_pcm.h b/frc971/wpilib/buffered_pcm.h
index f743371..4933c25 100644
--- a/frc971/wpilib/buffered_pcm.h
+++ b/frc971/wpilib/buffered_pcm.h
@@ -7,8 +7,7 @@
#include "frc971/wpilib/buffered_solenoid.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Manages setting values for all solenoids for a single PCM in a single CAN
// message.
@@ -43,7 +42,6 @@
friend class BufferedSolenoid;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_BUFFERED_PCM_H_
diff --git a/frc971/wpilib/can_drivetrain_writer.h b/frc971/wpilib/can_drivetrain_writer.h
index 1c0ba95..987605d 100644
--- a/frc971/wpilib/can_drivetrain_writer.h
+++ b/frc971/wpilib/can_drivetrain_writer.h
@@ -3,8 +3,7 @@
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class CANDrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
::frc971::control_loops::drivetrain::Output> {
@@ -30,5 +29,4 @@
std::vector<std::shared_ptr<TalonFX>> left_talonfxs_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/can_sensor_reader.h b/frc971/wpilib/can_sensor_reader.h
index 8ef5fd1..8eddfca 100644
--- a/frc971/wpilib/can_sensor_reader.h
+++ b/frc971/wpilib/can_sensor_reader.h
@@ -9,8 +9,7 @@
#include "aos/realtime.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class CANSensorReader {
public:
CANSensorReader(
@@ -37,6 +36,5 @@
// Callback used to send the CANPosition flatbuffer
std::function<void(ctre::phoenix::StatusCode status)> flatbuffer_callback_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_CAN_SENSOR_READER_H_
diff --git a/frc971/wpilib/dma_edge_counting.h b/frc971/wpilib/dma_edge_counting.h
index f51318d..eda77f0 100644
--- a/frc971/wpilib/dma_edge_counting.h
+++ b/frc971/wpilib/dma_edge_counting.h
@@ -14,8 +14,7 @@
#include "frc971/wpilib/dma.h"
#undef ERROR
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Generic interface for classes that do something with DMA samples and also
// poll current sensor values.
@@ -280,7 +279,6 @@
DISALLOW_COPY_AND_ASSIGN(DMASynchronizer);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_DMA_EDGE_COUNTING_H_
diff --git a/frc971/wpilib/drivetrain_writer.h b/frc971/wpilib/drivetrain_writer.h
index 195b5a3..e83585e 100644
--- a/frc971/wpilib/drivetrain_writer.h
+++ b/frc971/wpilib/drivetrain_writer.h
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/PWM.h"
#include "frc971/wpilib/loop_output_handler.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
::frc971::control_loops::drivetrain::Output> {
@@ -56,7 +55,6 @@
bool reversed_right0_, reversed_left0_, reversed_right1_, reversed_left1_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_DRIVETRAIN_WRITER_H_
diff --git a/frc971/wpilib/encoder_and_potentiometer.h b/frc971/wpilib/encoder_and_potentiometer.h
index 7ee85e1..a5eac24 100644
--- a/frc971/wpilib/encoder_and_potentiometer.h
+++ b/frc971/wpilib/encoder_and_potentiometer.h
@@ -14,8 +14,7 @@
#include "frc971/wpilib/dma.h"
#include "frc971/wpilib/dma_edge_counting.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Latches values from an encoder on positive edges from another input using
// DMA.
@@ -244,7 +243,6 @@
::std::unique_ptr<frc::Encoder> encoder_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_ENCODER_AND_POTENTIOMETER_H_
diff --git a/frc971/wpilib/fpga_time_conversion.h b/frc971/wpilib/fpga_time_conversion.h
index 51cc7a9..c279089 100644
--- a/frc971/wpilib/fpga_time_conversion.h
+++ b/frc971/wpilib/fpga_time_conversion.h
@@ -9,8 +9,7 @@
#include "aos/time/time.h"
#include "hal/cpp/fpga_clock.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Returns the offset from the monotonic clock to the FPGA time. This is defined
// as `fpga_time - monotonic_time`.
@@ -51,7 +50,6 @@
std::chrono::nanoseconds offset_ = std::chrono::nanoseconds::min();
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_FPGA_TIME_CONVERSION_H_
diff --git a/frc971/wpilib/generic_can_writer.h b/frc971/wpilib/generic_can_writer.h
index 7d6dd1a..d339324 100644
--- a/frc971/wpilib/generic_can_writer.h
+++ b/frc971/wpilib/generic_can_writer.h
@@ -5,8 +5,7 @@
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
/// This class uses a callback whenever it writes so that the caller can use any
/// flatbuffer to write to the talonfx motor.
@@ -70,5 +69,4 @@
write_callback_;
};
-} // namespace wpilib
-} // namespace frc971
\ No newline at end of file
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/gyro_interface.h b/frc971/wpilib/gyro_interface.h
index 3568a47..0c6b519 100644
--- a/frc971/wpilib/gyro_interface.h
+++ b/frc971/wpilib/gyro_interface.h
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/SPI.h"
#undef ERROR
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class GyroInterface {
public:
@@ -50,7 +49,6 @@
::std::unique_ptr<frc::SPI> gyro_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_GYRO_INTERFACE_H_
diff --git a/frc971/wpilib/gyro_sender.h b/frc971/wpilib/gyro_sender.h
index 4abfeaa..1c3f5d6 100644
--- a/frc971/wpilib/gyro_sender.h
+++ b/frc971/wpilib/gyro_sender.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/gyro_interface.h"
#include "frc971/zeroing/averager.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles reading the gyro over SPI and sending out angles on a queue.
//
@@ -56,7 +55,6 @@
bool zeroed_ = false;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_GYRO_H_
diff --git a/frc971/wpilib/interrupt_edge_counting.h b/frc971/wpilib/interrupt_edge_counting.h
index 5ea8df5..5d64582 100644
--- a/frc971/wpilib/interrupt_edge_counting.h
+++ b/frc971/wpilib/interrupt_edge_counting.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/ahal/DigitalInput.h"
#include "frc971/wpilib/ahal/Encoder.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class InterruptSynchronizer;
@@ -226,7 +225,6 @@
DISALLOW_COPY_AND_ASSIGN(InterruptSynchronizer);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_INTERRUPT_EDGE_COUNTING_H_
diff --git a/frc971/wpilib/joystick_sender.h b/frc971/wpilib/joystick_sender.h
index c9eb4cd..0591a8e 100644
--- a/frc971/wpilib/joystick_sender.h
+++ b/frc971/wpilib/joystick_sender.h
@@ -6,8 +6,7 @@
#include "aos/events/shm_event_loop.h"
#include "frc971/input/joystick_state_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class JoystickSender {
public:
@@ -19,7 +18,6 @@
const uint16_t team_id_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_JOYSTICK_SENDER_H_
diff --git a/frc971/wpilib/loop_output_handler.h b/frc971/wpilib/loop_output_handler.h
index 5f66a4c..1fb46b2 100644
--- a/frc971/wpilib/loop_output_handler.h
+++ b/frc971/wpilib/loop_output_handler.h
@@ -9,8 +9,7 @@
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles sending the output from a single control loop to the hardware.
//
@@ -64,7 +63,6 @@
::aos::TimerHandler *timer_handler_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_LOOP_OUTPUT_HANDLER_H_
diff --git a/frc971/wpilib/pdp_fetcher.h b/frc971/wpilib/pdp_fetcher.h
index 72f6745..38c4a5b 100644
--- a/frc971/wpilib/pdp_fetcher.h
+++ b/frc971/wpilib/pdp_fetcher.h
@@ -12,8 +12,7 @@
class PowerDistributionPanel;
} // namespace frc
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles fetching values from the PDP.
class PDPFetcher {
@@ -32,7 +31,6 @@
::std::unique_ptr<::frc::PowerDistributionPanel> pdp_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_PDP_FETCHER_H_
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index bf8c96a..455ed0e 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -21,8 +21,7 @@
using ::aos::monotonic_clock;
namespace chrono = ::std::chrono;
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class SensorReader {
public:
@@ -264,7 +263,6 @@
chrono::microseconds period_ = chrono::microseconds(5000);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_SENSOR_READER_H_
diff --git a/frc971/wpilib/spi_rx_clearer.h b/frc971/wpilib/spi_rx_clearer.h
index e385d21..733cf6f 100644
--- a/frc971/wpilib/spi_rx_clearer.h
+++ b/frc971/wpilib/spi_rx_clearer.h
@@ -3,8 +3,7 @@
#include <cstdint>
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Allows clearing the RX FIFO of the roboRIO's SPI peripheral on demand. This
// is necessary to work around a driver bug. See
@@ -35,7 +34,6 @@
bool RxFifoIsEmpty() { return !(ReadRegister(4) & (1 << 4)); }
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_SPI_RX_CLEARER_H_
diff --git a/frc971/wpilib/swerve/swerve_drivetrain_writer.h b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
index d02d4dc..8e9e616 100644
--- a/frc971/wpilib/swerve/swerve_drivetrain_writer.h
+++ b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
@@ -9,9 +9,7 @@
#include "frc971/wpilib/swerve/swerve_module.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
-namespace swerve {
+namespace frc971::wpilib::swerve {
// Reads from the swerve output flatbuffer and uses wpilib to set the current
// for each motor.
@@ -45,8 +43,6 @@
double max_voltage_;
};
-} // namespace swerve
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib::swerve
#endif // FRC971_WPILIB_SWERVE_DRIVETRAIN_WRITER_H_
diff --git a/frc971/wpilib/swerve/swerve_module.h b/frc971/wpilib/swerve/swerve_module.h
index d65547a..c373a31 100644
--- a/frc971/wpilib/swerve/swerve_module.h
+++ b/frc971/wpilib/swerve/swerve_module.h
@@ -3,9 +3,7 @@
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
-namespace swerve {
+namespace frc971::wpilib::swerve {
struct SwerveModule {
SwerveModule(TalonFXParams rotation_params, TalonFXParams translation_params,
@@ -39,7 +37,5 @@
std::shared_ptr<TalonFX> translation;
};
-} // namespace swerve
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib::swerve
#endif // FRC971_WPILIB_SWERVE_SWERVE_MODULE_H_
diff --git a/frc971/wpilib/talonfx.h b/frc971/wpilib/talonfx.h
index c25fa81..a3e3066 100644
--- a/frc971/wpilib/talonfx.h
+++ b/frc971/wpilib/talonfx.h
@@ -15,8 +15,7 @@
namespace control_loops = ::frc971::control_loops;
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
struct TalonFXParams {
int device_id;
@@ -100,6 +99,5 @@
double stator_current_limit_;
double supply_current_limit_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_TALONFX_MOTOR_H_
diff --git a/frc971/wpilib/wpilib_interface.h b/frc971/wpilib/wpilib_interface.h
index b992aa3..1d64d2c 100644
--- a/frc971/wpilib/wpilib_interface.h
+++ b/frc971/wpilib/wpilib_interface.h
@@ -6,14 +6,12 @@
#include "aos/events/event_loop.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Sends out a message on ::aos::robot_state.
flatbuffers::Offset<aos::RobotState> PopulateRobotState(
aos::Sender<::aos::RobotState>::Builder *builder, int32_t my_pid);
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_WPILIB_INTERFACE_H_
diff --git a/frc971/wpilib/wpilib_robot_base.h b/frc971/wpilib/wpilib_robot_base.h
index 6b9e5c5..27c1bcd 100644
--- a/frc971/wpilib/wpilib_robot_base.h
+++ b/frc971/wpilib/wpilib_robot_base.h
@@ -6,8 +6,7 @@
#include "aos/logging/logging.h"
#include "frc971/wpilib/ahal/RobotBase.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class WPILibRobotBase {
public:
@@ -81,7 +80,6 @@
T robot_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_NEWROBOTBASE_H_
diff --git a/frc971/wpilib/wpilib_utils.h b/frc971/wpilib/wpilib_utils.h
index 78dd262..0600f66 100644
--- a/frc971/wpilib/wpilib_utils.h
+++ b/frc971/wpilib/wpilib_utils.h
@@ -5,8 +5,7 @@
#include "frc971/constants.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Convert min and max angle positions from range to voltage and compare to
// min and max potentiometer voltage to check if in range.
@@ -22,7 +21,6 @@
::std::function<double(double)> pot_translate_inverse,
bool reverse, double limit_buffer = 0.05);
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_WPILIB_UTILS_H_
\ No newline at end of file
diff --git a/frc971/zeroing/absolute_and_absolute_encoder.h b/frc971/zeroing/absolute_and_absolute_encoder.h
index 509d5c5..90c8468 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder.h
+++ b/frc971/zeroing/absolute_and_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts and an absolute encoder that's not allowed to turn more
@@ -113,7 +112,6 @@
double position_ = 0.0;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ABSOLUTE_AND_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/absolute_encoder.h b/frc971/zeroing/absolute_encoder.h
index 9d730f2..b6fd579 100644
--- a/frc971/zeroing/absolute_encoder.h
+++ b/frc971/zeroing/absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts. The absolute encoder can't spin more than one
@@ -91,7 +90,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/averager.h b/frc971/zeroing/averager.h
index 0e15d13..370533f 100644
--- a/frc971/zeroing/averager.h
+++ b/frc971/zeroing/averager.h
@@ -8,8 +8,7 @@
#include "Eigen/Dense"
#include "glog/logging.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Averages a set of given numbers. Numbers are given one at a time. Once full
// the average may be requested.
@@ -89,7 +88,6 @@
size_t num_data_points_ = 0;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_AVERAGER_H_
diff --git a/frc971/zeroing/continuous_absolute_encoder.h b/frc971/zeroing/continuous_absolute_encoder.h
index e11d866..4994280 100644
--- a/frc971/zeroing/continuous_absolute_encoder.h
+++ b/frc971/zeroing/continuous_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which spins continuously. The
// absolute encoder must have a 1:1 ratio to the output.
@@ -93,7 +92,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_CONTINUOUS_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/hall_effect_and_position.h b/frc971/zeroing/hall_effect_and_position.h
index f03a442..d9f743f 100644
--- a/frc971/zeroing/hall_effect_and_position.h
+++ b/frc971/zeroing/hall_effect_and_position.h
@@ -5,8 +5,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an incremental encoder and a hall effect sensor.
class HallEffectAndPositionZeroingEstimator
@@ -84,7 +83,6 @@
double first_start_pos_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_HALL_EFFECT_AND_POSITION_H_
diff --git a/frc971/zeroing/pot_and_absolute_encoder.h b/frc971/zeroing/pot_and_absolute_encoder.h
index d250a50..f18e589 100644
--- a/frc971/zeroing/pot_and_absolute_encoder.h
+++ b/frc971/zeroing/pot_and_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts, and a potentiometer.
@@ -98,7 +97,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_POT_AND_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/pot_and_index.h b/frc971/zeroing/pot_and_index.h
index 473c674..cb28fe4 100644
--- a/frc971/zeroing/pot_and_index.h
+++ b/frc971/zeroing/pot_and_index.h
@@ -7,8 +7,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an incremental encoder with an index pulse and a
// potentiometer.
@@ -97,7 +96,6 @@
double first_start_pos_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_POT_AND_INDEX_H_
diff --git a/frc971/zeroing/pulse_index.h b/frc971/zeroing/pulse_index.h
index 4bcf210..9c17371 100644
--- a/frc971/zeroing/pulse_index.h
+++ b/frc971/zeroing/pulse_index.h
@@ -5,8 +5,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Zeros by seeing all the index pulses in the range of motion of the mechanism
// and using that to figure out which index pulse is which.
@@ -78,7 +77,6 @@
double position_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_PULSE_INDEX_H_
diff --git a/frc971/zeroing/zeroing.h b/frc971/zeroing/zeroing.h
index 5d5b6eb..8fe381d 100644
--- a/frc971/zeroing/zeroing.h
+++ b/frc971/zeroing/zeroing.h
@@ -20,8 +20,7 @@
// TODO(pschrader): Watch the offset over long periods of time and flag if it
// gets too far away from the initial value.
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
template <typename TPosition, typename TZeroingConstants, typename TState>
class ZeroingEstimator {
@@ -169,7 +168,6 @@
bool error_ = false;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ZEROING_H_
diff --git a/frc971/zeroing/zeroing_test.h b/frc971/zeroing/zeroing_test.h
index cadbe6c..497f833 100644
--- a/frc971/zeroing/zeroing_test.h
+++ b/frc971/zeroing/zeroing_test.h
@@ -4,9 +4,7 @@
#include "frc971/control_loops/position_sensor_sim.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using control_loops::PositionSensorSimulator;
using FBB = flatbuffers::FlatBufferBuilder;
@@ -27,6 +25,4 @@
}
};
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing