diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/sysid/SysIdRoutine.h b/wpilibNewCommands/src/main/native/include/frc2/command/sysid/SysIdRoutine.h index fe38971d63e..4ccfd41328d 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/sysid/SysIdRoutine.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/sysid/SysIdRoutine.h @@ -52,7 +52,8 @@ class Config { Config(std::optional rampRate, std::optional stepVoltage, std::optional timeout, - std::optional> recordState) { + std::function recordState) + : m_recordState{recordState} { if (rampRate) { m_rampRate = rampRate.value(); } @@ -62,9 +63,6 @@ class Config { if (timeout) { m_timeout = timeout.value(); } - if (recordState) { - m_recordState = recordState.value(); - } } }; @@ -109,7 +107,7 @@ class Mechanism { std::function log, frc2::Subsystem* subsystem, std::string_view name) : m_drive{std::move(drive)}, - m_log{std::move(log)}, + m_log{log ? std::move(log) : [](frc::sysid::SysIdRoutineLog* log) {}}, m_subsystem{subsystem}, m_name{name} {} @@ -134,7 +132,7 @@ class Mechanism { std::function log, frc2::Subsystem* subsystem) : m_drive{std::move(drive)}, - m_log{std::move(log)}, + m_log{log ? std::move(log) : [](frc::sysid::SysIdRoutineLog* log) {}}, m_subsystem{subsystem}, m_name{m_subsystem->GetName()} {} }; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/sysid/SysIdRoutineTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/sysid/SysIdRoutineTest.cpp index 5e4a5825ac3..1cfe39c6ee8 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/sysid/SysIdRoutineTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/sysid/SysIdRoutineTest.cpp @@ -63,6 +63,7 @@ class SysIdRoutineTest : public ::testing::Test { log->Motor("Mock Motor").position(0_m).velocity(0_mps).voltage(0_V); }, &m_subsystem}}; + frc2::CommandPtr m_quasistaticForward{ m_sysidRoutine.Quasistatic(frc2::sysid::Direction::kForward)}; frc2::CommandPtr m_quasistaticReverse{ @@ -72,6 +73,14 @@ class SysIdRoutineTest : public ::testing::Test { frc2::CommandPtr m_dynamicReverse{ m_sysidRoutine.Dynamic(frc2::sysid::Direction::kReverse)}; + frc2::sysid::SysIdRoutine m_emptySysidRoutine{ + frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, + frc2::sysid::Mechanism{[](units::volt_t driveVoltage) {}, nullptr, + &m_subsystem}}; + + frc2::CommandPtr m_emptyRoutineForward{ + m_emptySysidRoutine.Quasistatic(frc2::sysid::Direction::kForward)}; + void RunCommand(frc2::CommandPtr command) { command.get()->Initialize(); command.get()->Execute(); @@ -168,3 +177,8 @@ TEST_F(SysIdRoutineTest, OutputCorrectVoltage) { currentStateList.clear(); sentVoltages.clear(); } + +TEST_F(SysIdRoutineTest, EmptyLogFunc) { + RunCommand(std::move(m_emptyRoutineForward)); + SUCCEED(); +} diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h index 61d34f131f7..45d4fa3aab0 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h +++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Drive.h @@ -39,8 +39,7 @@ class Drive : public frc2::SubsystemBase { constants::drive::kRightEncoderReversed}; frc2::sysid::SysIdRoutine m_sysIdRoutine{ - frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, - std::nullopt}, + frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, frc2::sysid::Mechanism{ [this](units::volt_t driveVoltage) { m_leftMotor.SetVoltage(driveVoltage); diff --git a/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Shooter.h b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Shooter.h index 0a33db68ea3..4f10c18277d 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Shooter.h +++ b/wpilibcExamples/src/main/cpp/examples/SysId/include/subsystems/Shooter.h @@ -33,8 +33,7 @@ class Shooter : public frc2::SubsystemBase { constants::shooter::kEncoderReversed}; frc2::sysid::SysIdRoutine m_sysIdRoutine{ - frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, - std::nullopt}, + frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, frc2::sysid::Mechanism{ [this](units::volt_t driveVoltage) { m_shooterMotor.SetVoltage(driveVoltage);