mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
Rename tests for consistency (#3592)
I started with the output of styleguide#217, then renamed a few classes to fix compilation. ntcore's StorageTest needed some manual renaming since it put the Test word in the middle instead of at the end. One limitation of wpiformat is test cases that were only named "Test" were unmodified, and an error was generated. These test cases were manually given more descriptive names: * TimedRobotTest mode test cases had "Mode" appended to the name. Java tests were renamed to match. * UvAsyncTest and UvAsyncFunctionTest cases were given alternate names
This commit is contained in:
@@ -22,7 +22,7 @@ namespace frc {
|
||||
constexpr double kPositionStddev = 0.0001;
|
||||
constexpr auto kDt = 0.00505_s;
|
||||
|
||||
class StateSpace : public testing::Test {
|
||||
class StateSpaceTest : public testing::Test {
|
||||
public:
|
||||
LinearSystem<2, 1, 1> plant = [] {
|
||||
auto motors = DCMotor::Vex775Pro(2);
|
||||
@@ -51,7 +51,7 @@ void Update(const LinearSystem<2, 1, 1>& plant, LinearSystemLoop<2, 1, 1>& loop,
|
||||
loop.Predict(kDt);
|
||||
}
|
||||
|
||||
TEST_F(StateSpace, CorrectPredictLoop) {
|
||||
TEST_F(StateSpaceTest, CorrectPredictLoop) {
|
||||
std::default_random_engine generator;
|
||||
std::normal_distribution<double> dist{0.0, kPositionStddev};
|
||||
|
||||
|
||||
@@ -65,5 +65,5 @@ TEST_P(LinearFilterNoiseTest, NoiseReduce) {
|
||||
<< "Filter should have reduced noise accumulation but failed";
|
||||
}
|
||||
|
||||
INSTANTIATE_TEST_SUITE_P(Test, LinearFilterNoiseTest,
|
||||
INSTANTIATE_TEST_SUITE_P(Tests, LinearFilterNoiseTest,
|
||||
testing::Values(kTestSinglePoleIIR, kTestMovAvg));
|
||||
|
||||
@@ -115,7 +115,7 @@ TEST_P(LinearFilterOutputTest, Output) {
|
||||
<< "Filter output didn't match expected value";
|
||||
}
|
||||
|
||||
INSTANTIATE_TEST_SUITE_P(Test, LinearFilterOutputTest,
|
||||
INSTANTIATE_TEST_SUITE_P(Tests, LinearFilterOutputTest,
|
||||
testing::Values(kTestSinglePoleIIR, kTestHighPass,
|
||||
kTestMovAvg, kTestPulse));
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ TEST(Translation2dTest, Multiplication) {
|
||||
EXPECT_NEAR(mult.Y().to<double>(), 15.0, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(Translation2d, Division) {
|
||||
TEST(Translation2dTest, Division) {
|
||||
const Translation2d original{3.0_m, 5.0_m};
|
||||
const auto div = original / 2;
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
static constexpr double kEpsilon = 1E-9;
|
||||
|
||||
TEST(ChassisSpeeds, FieldRelativeConstruction) {
|
||||
TEST(ChassisSpeedsTest, FieldRelativeConstruction) {
|
||||
const auto chassisSpeeds = frc::ChassisSpeeds::FromFieldRelativeSpeeds(
|
||||
1.0_mps, 0.0_mps, 0.5_rad_per_s, frc::Rotation2d(-90.0_deg));
|
||||
|
||||
|
||||
@@ -15,7 +15,7 @@ using namespace frc;
|
||||
|
||||
static constexpr double kEpsilon = 1E-9;
|
||||
|
||||
TEST(DifferentialDriveKinematics, InverseKinematicsFromZero) {
|
||||
TEST(DifferentialDriveKinematicsTest, InverseKinematicsFromZero) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const ChassisSpeeds chassisSpeeds;
|
||||
const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
|
||||
@@ -24,7 +24,7 @@ TEST(DifferentialDriveKinematics, InverseKinematicsFromZero) {
|
||||
EXPECT_NEAR(wheelSpeeds.right.to<double>(), 0, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(DifferentialDriveKinematics, ForwardKinematicsFromZero) {
|
||||
TEST(DifferentialDriveKinematicsTest, ForwardKinematicsFromZero) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const DifferentialDriveWheelSpeeds wheelSpeeds;
|
||||
const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
|
||||
@@ -34,7 +34,7 @@ TEST(DifferentialDriveKinematics, ForwardKinematicsFromZero) {
|
||||
EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(DifferentialDriveKinematics, InverseKinematicsForStraightLine) {
|
||||
TEST(DifferentialDriveKinematicsTest, InverseKinematicsForStraightLine) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const ChassisSpeeds chassisSpeeds{3.0_mps, 0_mps, 0_rad_per_s};
|
||||
const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds);
|
||||
@@ -43,7 +43,7 @@ TEST(DifferentialDriveKinematics, InverseKinematicsForStraightLine) {
|
||||
EXPECT_NEAR(wheelSpeeds.right.to<double>(), 3, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(DifferentialDriveKinematics, ForwardKinematicsForStraightLine) {
|
||||
TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForStraightLine) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const DifferentialDriveWheelSpeeds wheelSpeeds{3.0_mps, 3.0_mps};
|
||||
const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds);
|
||||
@@ -53,7 +53,7 @@ TEST(DifferentialDriveKinematics, ForwardKinematicsForStraightLine) {
|
||||
EXPECT_NEAR(chassisSpeeds.omega.to<double>(), 0, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(DifferentialDriveKinematics, InverseKinematicsForRotateInPlace) {
|
||||
TEST(DifferentialDriveKinematicsTest, InverseKinematicsForRotateInPlace) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const ChassisSpeeds chassisSpeeds{
|
||||
0.0_mps, 0.0_mps, units::radians_per_second_t{wpi::numbers::pi}};
|
||||
@@ -65,7 +65,7 @@ TEST(DifferentialDriveKinematics, InverseKinematicsForRotateInPlace) {
|
||||
kEpsilon);
|
||||
}
|
||||
|
||||
TEST(DifferentialDriveKinematics, ForwardKinematicsForRotateInPlace) {
|
||||
TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForRotateInPlace) {
|
||||
const DifferentialDriveKinematics kinematics{0.381_m * 2};
|
||||
const DifferentialDriveWheelSpeeds wheelSpeeds{
|
||||
units::meters_per_second_t(+0.381 * wpi::numbers::pi),
|
||||
|
||||
@@ -12,7 +12,7 @@ static constexpr double kEpsilon = 1E-9;
|
||||
|
||||
using namespace frc;
|
||||
|
||||
TEST(DifferentialDriveOdometry, EncoderDistances) {
|
||||
TEST(DifferentialDriveOdometryTest, EncoderDistances) {
|
||||
DifferentialDriveOdometry odometry{Rotation2d(45_deg)};
|
||||
|
||||
const auto& pose = odometry.Update(Rotation2d(135_deg), 0_m,
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
static constexpr double kEpsilon = 1E-9;
|
||||
|
||||
TEST(SwerveModuleState, Optimize) {
|
||||
TEST(SwerveModuleStateTest, Optimize) {
|
||||
frc::Rotation2d angleA{45_deg};
|
||||
frc::SwerveModuleState refA{-2_mps, 180_deg};
|
||||
auto optimizedA = frc::SwerveModuleState::Optimize(refA, angleA);
|
||||
@@ -24,7 +24,7 @@ TEST(SwerveModuleState, Optimize) {
|
||||
EXPECT_NEAR(optimizedB.angle.Degrees().to<double>(), -139.0, kEpsilon);
|
||||
}
|
||||
|
||||
TEST(SwerveModuleState, NoOptimize) {
|
||||
TEST(SwerveModuleStateTest, NoOptimize) {
|
||||
frc::Rotation2d angleA{0_deg};
|
||||
frc::SwerveModuleState refA{2_mps, 89_deg};
|
||||
auto optimizedA = frc::SwerveModuleState::Optimize(refA, angleA);
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
#include "frc/trajectory/TrajectoryGenerator.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
TEST(TrajectoryConcatenate, States) {
|
||||
TEST(TrajectoryConcatenateTest, States) {
|
||||
auto t1 = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
{}, {}, {1_m, 1_m, 0_deg}, {2_mps, 2_mps_sq});
|
||||
auto t2 = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
|
||||
@@ -28,7 +28,7 @@ void TestSameShapedTrajectory(std::vector<frc::Trajectory::State> statesA,
|
||||
}
|
||||
}
|
||||
|
||||
TEST(TrajectoryTransforms, TransformBy) {
|
||||
TEST(TrajectoryTransformsTest, TransformBy) {
|
||||
frc::TrajectoryConfig config{3_mps, 3_mps_sq};
|
||||
auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
frc::Pose2d{}, {}, frc::Pose2d{1_m, 1_m, frc::Rotation2d(90_deg)},
|
||||
@@ -46,7 +46,7 @@ TEST(TrajectoryTransforms, TransformBy) {
|
||||
TestSameShapedTrajectory(trajectory.States(), transformedTrajectory.States());
|
||||
}
|
||||
|
||||
TEST(TrajectoryTransforms, RelativeTo) {
|
||||
TEST(TrajectoryTransformsTest, RelativeTo) {
|
||||
frc::TrajectoryConfig config{3_mps, 3_mps_sq};
|
||||
auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
|
||||
frc::Pose2d{1_m, 2_m, frc::Rotation2d(30_deg)}, {},
|
||||
|
||||
Reference in New Issue
Block a user