[wpilibc] Transition C++ classes to units::second_t (#3396)

A lot of these are breaking changes. frc::Timer was replaced with the
contents of frc2::Timer. The others were in-place argument changes or
removing deprecated non-unit overloads.
This commit is contained in:
Tyler Veness
2021-05-28 22:06:59 -07:00
committed by GitHub
parent 827b17a52b
commit e09293a15e
99 changed files with 503 additions and 790 deletions

View File

@@ -359,12 +359,13 @@ void CommandScheduler::CancelAll() {
Cancel(commands);
}
double CommandScheduler::TimeSinceScheduled(const Command* command) const {
units::second_t CommandScheduler::TimeSinceScheduled(
const Command* command) const {
auto find = m_impl->scheduledCommands.find(command);
if (find != m_impl->scheduledCommands.end()) {
return find->second.TimeSinceInitialized();
} else {
return -1;
return -1_s;
}
}
bool CommandScheduler::IsScheduled(

View File

@@ -16,9 +16,12 @@ CommandState::CommandState(bool interruptible)
void CommandState::StartTiming() {
m_startTime = frc::Timer::GetFPGATimestamp();
}
void CommandState::StartRunning() {
m_startTime = -1;
m_startTime = -1_s;
}
double CommandState::TimeSinceInitialized() const {
return m_startTime != -1 ? frc::Timer::GetFPGATimestamp() - m_startTime : -1;
units::second_t CommandState::TimeSinceInitialized() const {
return m_startTime != -1_s ? frc::Timer::GetFPGATimestamp() - m_startTime
: -1_s;
}

View File

@@ -4,7 +4,7 @@
#include "frc2/command/WaitUntilCommand.h"
#include "frc2/Timer.h"
#include <frc/Timer.h>
using namespace frc2;
@@ -12,7 +12,7 @@ WaitUntilCommand::WaitUntilCommand(std::function<bool()> condition)
: m_condition{std::move(condition)} {}
WaitUntilCommand::WaitUntilCommand(units::second_t time)
: m_condition{[=] { return Timer::GetMatchTime() - time > 0_s; }} {}
: m_condition{[=] { return frc::Timer::GetMatchTime() - time > 0_s; }} {}
bool WaitUntilCommand::IsFinished() {
return m_condition();

View File

@@ -249,9 +249,9 @@ class CommandScheduler final : public frc::Sendable,
* them.
*
* @param command the command to query
* @return the time since the command was scheduled, in seconds
* @return the time since the command was scheduled
*/
double TimeSinceScheduled(const Command* command) const;
units::second_t TimeSinceScheduled(const Command* command) const;
/**
* Whether the given commands are running. Note that this only works on

View File

@@ -4,6 +4,8 @@
#pragma once
#include <units/time.h>
namespace frc2 {
/**
* Class that holds scheduling state for a command. Used internally by the
@@ -18,10 +20,10 @@ class CommandState final {
bool IsInterruptible() const { return m_interruptible; }
// The time since this command was initialized.
double TimeSinceInitialized() const;
units::second_t TimeSinceInitialized() const;
private:
double m_startTime = -1;
units::second_t m_startTime = -1_s;
bool m_interruptible;
void StartTiming();

View File

@@ -7,6 +7,7 @@
#include <initializer_list>
#include <memory>
#include <frc/Timer.h>
#include <frc/controller/HolonomicDriveController.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
@@ -24,7 +25,6 @@
#include "CommandBase.h"
#include "CommandHelper.h"
#include "frc2/Timer.h"
#pragma once
@@ -444,7 +444,7 @@ class MecanumControllerCommand
m_outputVolts;
bool m_usePID;
frc2::Timer m_timer;
frc::Timer m_timer;
frc::MecanumDriveWheelSpeeds m_prevSpeeds;
units::second_t m_prevTime;
};

View File

@@ -8,6 +8,7 @@
#include <initializer_list>
#include <memory>
#include <frc/Timer.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/RamseteController.h>
#include <frc/controller/SimpleMotorFeedforward.h>
@@ -18,7 +19,6 @@
#include <units/voltage.h>
#include <wpi/ArrayRef.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -185,7 +185,7 @@ class RamseteCommand : public CommandHelper<CommandBase, RamseteCommand> {
std::function<void(units::meters_per_second_t, units::meters_per_second_t)>
m_outputVel;
Timer m_timer;
frc::Timer m_timer;
units::second_t m_prevTime;
frc::DifferentialDriveWheelSpeeds m_prevSpeeds;
bool m_usePID;

View File

@@ -7,6 +7,7 @@
#include <initializer_list>
#include <memory>
#include <frc/Timer.h>
#include <frc/controller/HolonomicDriveController.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
@@ -22,7 +23,6 @@
#include "CommandBase.h"
#include "CommandHelper.h"
#include "frc2/Timer.h"
#pragma once
@@ -225,7 +225,7 @@ class SwerveControllerCommand
std::function<frc::Rotation2d()> m_desiredRotation;
frc2::Timer m_timer;
frc::Timer m_timer;
units::second_t m_prevTime;
frc::Rotation2d m_finalRotation;
};

View File

@@ -7,10 +7,10 @@
#include <functional>
#include <initializer_list>
#include <frc/Timer.h>
#include <frc/trajectory/TrapezoidProfile.h>
#include <wpi/ArrayRef.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -76,7 +76,7 @@ class TrapezoidProfileCommand
frc::TrapezoidProfile<Distance> m_profile;
std::function<void(State)> m_output;
Timer m_timer;
frc::Timer m_timer;
};
} // namespace frc2

View File

@@ -4,9 +4,9 @@
#pragma once
#include <frc/Timer.h>
#include <units/time.h>
#include "frc2/Timer.h"
#include "frc2/command/CommandBase.h"
#include "frc2/command/CommandHelper.h"
@@ -39,7 +39,7 @@ class WaitCommand : public CommandHelper<CommandBase, WaitCommand> {
bool RunsWhenDisabled() const override;
protected:
Timer m_timer;
frc::Timer m_timer;
private:
units::second_t m_duration;

View File

@@ -2,10 +2,10 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <frc2/Timer.h>
#include <frc2/command/MecanumControllerCommand.h>
#include <frc2/command/Subsystem.h>
#include <frc/Timer.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/geometry/Rotation2d.h>
@@ -27,7 +27,7 @@ class MecanumControllerCommandTest : public ::testing::Test {
units::inverse<units::squared<units::second>>>;
protected:
frc2::Timer m_timer;
frc::Timer m_timer;
frc::Rotation2d m_angle{0_rad};
units::meters_per_second_t m_frontLeftSpeed = 0.0_mps;

View File

@@ -2,10 +2,10 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <frc2/Timer.h>
#include <frc2/command/Subsystem.h>
#include <frc2/command/SwerveControllerCommand.h>
#include <frc/Timer.h>
#include <frc/controller/PIDController.h>
#include <frc/controller/ProfiledPIDController.h>
#include <frc/geometry/Rotation2d.h>
@@ -28,7 +28,7 @@ class SwerveControllerCommandTest : public ::testing::Test {
units::inverse<units::squared<units::second>>>;
protected:
frc2::Timer m_timer;
frc::Timer m_timer;
frc::Rotation2d m_angle{0_rad};
wpi::array<frc::SwerveModuleState, 4> m_moduleStates{

View File

@@ -153,7 +153,7 @@ double PIDBase::GetSetpoint() const {
double PIDBase::GetDeltaSetpoint() const {
std::scoped_lock lock(m_thisMutex);
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get().to<double>();
}
double PIDBase::GetError() const {

View File

@@ -19,20 +19,21 @@ using namespace frc;
int Command::m_commandCounter = 0;
Command::Command() : Command("", -1.0) {}
Command::Command() : Command("", -1_s) {}
Command::Command(std::string_view name) : Command(name, -1.0) {}
Command::Command(std::string_view name) : Command(name, -1_s) {}
Command::Command(double timeout) : Command("", timeout) {}
Command::Command(units::second_t timeout) : Command("", timeout) {}
Command::Command(Subsystem& subsystem) : Command("", -1.0) {
Command::Command(Subsystem& subsystem) : Command("", -1_s) {
Requires(&subsystem);
}
Command::Command(std::string_view name, double timeout) {
Command::Command(std::string_view name, units::second_t timeout) {
// We use -1.0 to indicate no timeout.
if (timeout < 0.0 && timeout != -1.0) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0.0", timeout);
if (timeout < 0_s && timeout != -1_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
}
m_timeout = timeout;
@@ -47,22 +48,24 @@ Command::Command(std::string_view name, double timeout) {
}
Command::Command(std::string_view name, Subsystem& subsystem)
: Command(name, -1.0) {
: Command(name, -1_s) {
Requires(&subsystem);
}
Command::Command(double timeout, Subsystem& subsystem) : Command("", timeout) {
Command::Command(units::second_t timeout, Subsystem& subsystem)
: Command("", timeout) {
Requires(&subsystem);
}
Command::Command(std::string_view name, double timeout, Subsystem& subsystem)
Command::Command(std::string_view name, units::second_t timeout,
Subsystem& subsystem)
: Command(name, timeout) {
Requires(&subsystem);
}
double Command::TimeSinceInitialized() const {
if (m_startTime < 0.0) {
return 0.0;
units::second_t Command::TimeSinceInitialized() const {
if (m_startTime < 0_s) {
return 0_s;
} else {
return Timer::GetFPGATimestamp() - m_startTime;
}
@@ -170,16 +173,17 @@ int Command::GetID() const {
return m_commandID;
}
void Command::SetTimeout(double timeout) {
if (timeout < 0.0) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0.0", timeout);
void Command::SetTimeout(units::second_t timeout) {
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
} else {
m_timeout = timeout;
}
}
bool Command::IsTimedOut() const {
return m_timeout != -1 && TimeSinceInitialized() >= m_timeout;
return m_timeout != -1_s && TimeSinceInitialized() >= m_timeout;
}
bool Command::AssertUnlocked(std::string_view message) {
@@ -264,7 +268,7 @@ void Command::Removed() {
void Command::StartRunning() {
m_running = true;
m_startTime = -1;
m_startTime = -1_s;
m_completed = false;
}

View File

@@ -29,15 +29,16 @@ void CommandGroup::AddSequential(Command* command) {
}
}
void CommandGroup::AddSequential(Command* command, double timeout) {
void CommandGroup::AddSequential(Command* command, units::second_t timeout) {
if (!command) {
throw FRC_MakeError(err::NullParameter, "{}", "command");
}
if (!AssertUnlocked("Cannot add new command to command group")) {
return;
}
if (timeout < 0.0) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0.0", timeout);
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
}
m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence,
@@ -72,15 +73,16 @@ void CommandGroup::AddParallel(Command* command) {
}
}
void CommandGroup::AddParallel(Command* command, double timeout) {
void CommandGroup::AddParallel(Command* command, units::second_t timeout) {
if (!command) {
throw FRC_MakeError(err::NullParameter, "{}", "command");
}
if (!AssertUnlocked("Cannot add new command to command group")) {
return;
}
if (timeout < 0.0) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0.0", timeout);
if (timeout < 0_s) {
throw FRC_MakeError(err::ParameterOutOfRange, "timeout {} < 0 s",
timeout.to<double>());
}
m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild,

View File

@@ -9,15 +9,15 @@
using namespace frc;
CommandGroupEntry::CommandGroupEntry(Command* command, Sequence state,
double timeout)
units::second_t timeout)
: m_timeout(timeout), m_command(command), m_state(state) {}
bool CommandGroupEntry::IsTimedOut() const {
if (m_timeout < 0.0) {
if (m_timeout < 0_s) {
return false;
}
double time = m_command->TimeSinceInitialized();
if (time == 0.0) {
auto time = m_command->TimeSinceInitialized();
if (time == 0_s) {
return false;
}
return time >= m_timeout;

View File

@@ -6,16 +6,16 @@
using namespace frc;
TimedCommand::TimedCommand(std::string_view name, double timeout)
TimedCommand::TimedCommand(std::string_view name, units::second_t timeout)
: Command(name, timeout) {}
TimedCommand::TimedCommand(double timeout) : Command(timeout) {}
TimedCommand::TimedCommand(units::second_t timeout) : Command(timeout) {}
TimedCommand::TimedCommand(std::string_view name, double timeout,
TimedCommand::TimedCommand(std::string_view name, units::second_t timeout,
Subsystem& subsystem)
: Command(name, timeout, subsystem) {}
TimedCommand::TimedCommand(double timeout, Subsystem& subsystem)
TimedCommand::TimedCommand(units::second_t timeout, Subsystem& subsystem)
: Command(timeout, subsystem) {}
bool TimedCommand::IsFinished() {

View File

@@ -8,8 +8,8 @@
using namespace frc;
WaitCommand::WaitCommand(double timeout)
: TimedCommand(fmt::format("Wait({})", timeout), timeout) {}
WaitCommand::WaitCommand(units::second_t timeout)
: TimedCommand(fmt::format("Wait({})", timeout.to<double>()), timeout) {}
WaitCommand::WaitCommand(std::string_view name, double timeout)
WaitCommand::WaitCommand(std::string_view name, units::second_t timeout)
: TimedCommand(name, timeout) {}

View File

@@ -8,10 +8,10 @@
using namespace frc;
WaitForChildren::WaitForChildren(double timeout)
WaitForChildren::WaitForChildren(units::second_t timeout)
: Command("WaitForChildren", timeout) {}
WaitForChildren::WaitForChildren(std::string_view name, double timeout)
WaitForChildren::WaitForChildren(std::string_view name, units::second_t timeout)
: Command(name, timeout) {}
bool WaitForChildren::IsFinished() {

View File

@@ -8,12 +8,12 @@
using namespace frc;
WaitUntilCommand::WaitUntilCommand(double time)
WaitUntilCommand::WaitUntilCommand(units::second_t time)
: Command("WaitUntilCommand", time) {
m_time = time;
}
WaitUntilCommand::WaitUntilCommand(std::string_view name, double time)
WaitUntilCommand::WaitUntilCommand(std::string_view name, units::second_t time)
: Command(name, time) {
m_time = time;
}

View File

@@ -8,6 +8,7 @@
#include <string>
#include <string_view>
#include <units/time.h>
#include <wpi/SmallPtrSet.h>
#include "frc/commands/Subsystem.h"
@@ -64,10 +65,10 @@ class Command : public Sendable, public SendableHelper<Command> {
/**
* Creates a new command with the given timeout and a default name.
*
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @see IsTimedOut()
*/
explicit Command(double timeout);
explicit Command(units::second_t timeout);
/**
* Creates a new command with the given timeout and a default name.
@@ -80,10 +81,10 @@ class Command : public Sendable, public SendableHelper<Command> {
* Creates a new command with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @see IsTimedOut()
*/
Command(std::string_view name, double timeout);
Command(std::string_view name, units::second_t timeout);
/**
* Creates a new command with the given name and timeout.
@@ -96,19 +97,19 @@ class Command : public Sendable, public SendableHelper<Command> {
/**
* Creates a new command with the given name and timeout.
*
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @param subsystem the subsystem that the command requires @see IsTimedOut()
*/
Command(double timeout, Subsystem& subsystem);
Command(units::second_t timeout, Subsystem& subsystem);
/**
* Creates a new command with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @param subsystem the subsystem that the command requires @see IsTimedOut()
*/
Command(std::string_view name, double timeout, Subsystem& subsystem);
Command(std::string_view name, units::second_t timeout, Subsystem& subsystem);
~Command() override = default;
@@ -116,13 +117,13 @@ class Command : public Sendable, public SendableHelper<Command> {
Command& operator=(Command&&) = default;
/**
* Returns the time since this command was initialized (in seconds).
* Returns the time since this command was initialized.
*
* This function will work even if there is no specified timeout.
*
* @return the time since this command was initialized (in seconds).
* @return the time since this command was initialized.
*/
double TimeSinceInitialized() const;
units::second_t TimeSinceInitialized() const;
/**
* This method specifies that the given Subsystem is used by this command.
@@ -271,10 +272,10 @@ class Command : public Sendable, public SendableHelper<Command> {
/**
* Sets the timeout of this command.
*
* @param timeout the timeout (in seconds)
* @param timeout the timeout
* @see IsTimedOut()
*/
void SetTimeout(double timeout);
void SetTimeout(units::second_t timeout);
/**
* Returns whether or not the TimeSinceInitialized() method returns a number
@@ -445,10 +446,10 @@ class Command : public Sendable, public SendableHelper<Command> {
void StartTiming();
// The time since this command was initialized
double m_startTime = -1;
units::second_t m_startTime = -1_s;
// The time (in seconds) before this command "times out" (-1 if no timeout)
double m_timeout;
units::second_t m_timeout;
// Whether or not this command has been initialized
bool m_initialized = false;

View File

@@ -7,6 +7,8 @@
#include <string_view>
#include <vector>
#include <units/time.h>
#include "frc/commands/Command.h"
#include "frc/commands/CommandGroupEntry.h"
@@ -74,9 +76,9 @@ class CommandGroup : public Command {
* It is recommended that this method be called in the constructor.
*
* @param command The Command to be added
* @param timeout The timeout (in seconds)
* @param timeout The timeout
*/
void AddSequential(Command* command, double timeout);
void AddSequential(Command* command, units::second_t timeout);
/**
* Adds a new child Command to the group. The Command will be started after
@@ -121,9 +123,9 @@ class CommandGroup : public Command {
* It is recommended that this method be called in the constructor.
*
* @param command The command to be added
* @param timeout The timeout (in seconds)
* @param timeout The timeout
*/
void AddParallel(Command* command, double timeout);
void AddParallel(Command* command, units::second_t timeout);
bool IsInterruptible() const;

View File

@@ -4,6 +4,8 @@
#pragma once
#include <units/time.h>
namespace frc {
class Command;
@@ -17,14 +19,15 @@ class CommandGroupEntry {
};
CommandGroupEntry() = default;
CommandGroupEntry(Command* command, Sequence state, double timeout = -1.0);
CommandGroupEntry(Command* command, Sequence state,
units::second_t timeout = -1_s);
CommandGroupEntry(CommandGroupEntry&&) = default;
CommandGroupEntry& operator=(CommandGroupEntry&&) = default;
bool IsTimedOut() const;
double m_timeout = -1.0;
units::second_t m_timeout = -1_s;
Command* m_command = nullptr;
Sequence m_state = kSequence_InSequence;
};

View File

@@ -6,6 +6,8 @@
#include <string_view>
#include <units/time.h>
#include "frc/commands/Command.h"
namespace frc {
@@ -21,33 +23,34 @@ class TimedCommand : public Command {
* Creates a new TimedCommand with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
*/
TimedCommand(std::string_view name, double timeout);
TimedCommand(std::string_view name, units::second_t timeout);
/**
* Creates a new WaitCommand with the given timeout.
*
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
*/
explicit TimedCommand(double timeout);
explicit TimedCommand(units::second_t timeout);
/**
* Creates a new TimedCommand with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @param subsystem the subsystem that the command requires
*/
TimedCommand(std::string_view name, double timeout, Subsystem& subsystem);
TimedCommand(std::string_view name, units::second_t timeout,
Subsystem& subsystem);
/**
* Creates a new WaitCommand with the given timeout.
*
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
* @param subsystem the subsystem that the command requires
*/
TimedCommand(double timeout, Subsystem& subsystem);
TimedCommand(units::second_t timeout, Subsystem& subsystem);
~TimedCommand() override = default;

View File

@@ -6,6 +6,8 @@
#include <string_view>
#include <units/time.h>
#include "frc/commands/TimedCommand.h"
namespace frc {
@@ -16,16 +18,16 @@ class WaitCommand : public TimedCommand {
* Creates a new WaitCommand with the given name and timeout.
*
* @param name the name of the command
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
*/
explicit WaitCommand(double timeout);
explicit WaitCommand(units::second_t timeout);
/**
* Creates a new WaitCommand with the given timeout.
*
* @param timeout the time (in seconds) before this command "times out"
* @param timeout the time before this command "times out"
*/
WaitCommand(std::string_view name, double timeout);
WaitCommand(std::string_view name, units::second_t timeout);
~WaitCommand() override = default;

View File

@@ -6,14 +6,16 @@
#include <string_view>
#include <units/time.h>
#include "frc/commands/Command.h"
namespace frc {
class WaitForChildren : public Command {
public:
explicit WaitForChildren(double timeout);
WaitForChildren(std::string_view name, double timeout);
explicit WaitForChildren(units::second_t timeout);
WaitForChildren(std::string_view name, units::second_t timeout);
~WaitForChildren() override = default;
WaitForChildren(WaitForChildren&&) = default;

View File

@@ -6,6 +6,8 @@
#include <string_view>
#include <units/time.h>
#include "frc/commands/Command.h"
namespace frc {
@@ -20,9 +22,9 @@ class WaitUntilCommand : public Command {
*
* @see CommandGroup
*/
explicit WaitUntilCommand(double time);
explicit WaitUntilCommand(units::second_t time);
WaitUntilCommand(std::string_view name, double time);
WaitUntilCommand(std::string_view name, units::second_t time);
~WaitUntilCommand() override = default;
@@ -36,7 +38,7 @@ class WaitUntilCommand : public Command {
bool IsFinished() override;
private:
double m_time;
units::second_t m_time;
};
} // namespace frc

View File

@@ -13,8 +13,8 @@
using namespace frc;
static constexpr auto kSamplePeriod = 0.0005_s;
static constexpr double kCalibrationSampleTime = 5.0;
static constexpr auto kSamplePeriod = 0.5_ms;
static constexpr auto kCalibrationSampleTime = 5_s;
static constexpr double kDegreePerSecondPerLSB = 0.0125;
// static constexpr int kRateRegister = 0x00;
@@ -121,7 +121,7 @@ void ADXRS450_Gyro::Reset() {
}
void ADXRS450_Gyro::Calibrate() {
Wait(0.1);
Wait(100_ms);
m_spi.SetAccumulatorIntegratedCenter(0);
m_spi.ResetAccumulator();

View File

@@ -141,7 +141,7 @@ void AnalogInput::ResetAccumulator() {
const double sampleTime = 1.0 / GetSampleRate();
const double overSamples = 1 << GetOversampleBits();
const double averageSamples = 1 << GetAverageBits();
Wait(sampleTime * overSamples * averageSamples);
Wait(units::second_t{sampleTime * overSamples * averageSamples});
}
void AnalogInput::SetAccumulatorCenter(int center) {

View File

@@ -24,7 +24,7 @@ Counter::Counter(Mode mode) {
&m_index, &status);
FRC_CheckErrorStatus(status, "{}", "InitializeCounter");
SetMaxPeriod(0.5);
SetMaxPeriod(0.5_s);
HAL_Report(HALUsageReporting::kResourceType_Counter, m_index + 1, mode + 1);
SendableRegistry::GetInstance().AddLW(this, "Counter", m_index);
@@ -273,16 +273,16 @@ void Counter::Reset() {
FRC_CheckErrorStatus(status, "{}", "Reset");
}
double Counter::GetPeriod() const {
units::second_t Counter::GetPeriod() const {
int32_t status = 0;
double value = HAL_GetCounterPeriod(m_counter, &status);
FRC_CheckErrorStatus(status, "{}", "GetPeriod");
return value;
return units::second_t{value};
}
void Counter::SetMaxPeriod(double maxPeriod) {
void Counter::SetMaxPeriod(units::second_t maxPeriod) {
int32_t status = 0;
HAL_SetCounterMaxPeriod(m_counter, maxPeriod, &status);
HAL_SetCounterMaxPeriod(m_counter, maxPeriod.to<double>(), &status);
FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
}

View File

@@ -89,7 +89,7 @@ class MatchDataSender {
using namespace frc;
static constexpr double kJoystickUnpluggedMessageInterval = 1.0;
static constexpr auto kJoystickUnpluggedMessageInterval = 1_s;
static int& GetDSLastCount() {
// There is a rollover error condition here. At Packet# = n * (uintmax), this
@@ -485,12 +485,12 @@ int DriverStation::GetLocation() const {
}
void DriverStation::WaitForData() {
WaitForData(0);
WaitForData(0_s);
}
bool DriverStation::WaitForData(double timeout) {
auto timeoutTime =
std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
bool DriverStation::WaitForData(units::second_t timeout) {
auto timeoutTime = std::chrono::steady_clock::now() +
std::chrono::steady_clock::duration{timeout};
std::unique_lock lock(m_waitForDataMutex);
int& lastCount = GetDSLastCount();
@@ -500,7 +500,7 @@ bool DriverStation::WaitForData(double timeout) {
return true;
}
while (m_waitForDataCounter == currentCount) {
if (timeout > 0) {
if (timeout > 0_s) {
auto timedOut = m_waitForDataCond.wait_until(lock, timeoutTime);
if (timedOut == std::cv_status::timeout) {
return false;
@@ -586,7 +586,7 @@ DriverStation::DriverStation() {
void DriverStation::ReportJoystickUnpluggedErrorV(fmt::string_view format,
fmt::format_args args) {
double currentTime = Timer::GetFPGATimestamp();
auto currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportErrorV(err::Error, "", 0, "", format, args);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
@@ -596,7 +596,7 @@ void DriverStation::ReportJoystickUnpluggedErrorV(fmt::string_view format,
void DriverStation::ReportJoystickUnpluggedWarningV(fmt::string_view format,
fmt::format_args args) {
if (IsFMSAttached() || !m_silenceJoystickWarning) {
double currentTime = Timer::GetFPGATimestamp();
auto currentTime = Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
ReportErrorV(warn::Warning, "", 0, "", format, args);
m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;

View File

@@ -79,16 +79,16 @@ void Encoder::Reset() {
FRC_CheckErrorStatus(status, "{}", "Reset");
}
double Encoder::GetPeriod() const {
units::second_t Encoder::GetPeriod() const {
int32_t status = 0;
double value = HAL_GetEncoderPeriod(m_encoder, &status);
FRC_CheckErrorStatus(status, "{}", "GetPeriod");
return value;
return units::second_t{value};
}
void Encoder::SetMaxPeriod(double maxPeriod) {
void Encoder::SetMaxPeriod(units::second_t maxPeriod) {
int32_t status = 0;
HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod, &status);
HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.to<double>(), &status);
FRC_CheckErrorStatus(status, "{}", "SetMaxPeriod");
}

View File

@@ -85,12 +85,13 @@ void InterruptableSensorBase::CancelInterrupts() {
}
InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
double timeout, bool ignorePrevious) {
units::second_t timeout, bool ignorePrevious) {
FRC_Assert(m_interrupt != HAL_kInvalidHandle);
int32_t status = 0;
int result;
result = HAL_WaitForInterrupt(m_interrupt, timeout, ignorePrevious, &status);
result = HAL_WaitForInterrupt(m_interrupt, timeout.to<double>(),
ignorePrevious, &status);
FRC_CheckErrorStatus(status, "{}", "WaitForInterrupt");
// Rising edge result is the interrupt bit set in the byte 0xFF
@@ -116,20 +117,20 @@ void InterruptableSensorBase::DisableInterrupts() {
FRC_CheckErrorStatus(status, "{}", "DisableInterrupts");
}
double InterruptableSensorBase::ReadRisingTimestamp() {
units::second_t InterruptableSensorBase::ReadRisingTimestamp() {
FRC_Assert(m_interrupt != HAL_kInvalidHandle);
int32_t status = 0;
int64_t timestamp = HAL_ReadInterruptRisingTimestamp(m_interrupt, &status);
FRC_CheckErrorStatus(status, "{}", "ReadRisingTimestamp");
return timestamp * 1e-6;
return units::microsecond_t(timestamp);
}
double InterruptableSensorBase::ReadFallingTimestamp() {
units::second_t InterruptableSensorBase::ReadFallingTimestamp() {
FRC_Assert(m_interrupt != HAL_kInvalidHandle);
int32_t status = 0;
int64_t timestamp = HAL_ReadInterruptFallingTimestamp(m_interrupt, &status);
FRC_CheckErrorStatus(status, "{}", "ReadFallingTimestamp");
return timestamp * 1e-6;
return units::microsecond_t(timestamp);
}
void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,

View File

@@ -47,12 +47,12 @@ void MotorSafety::Feed() {
m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
}
void MotorSafety::SetExpiration(double expirationTime) {
void MotorSafety::SetExpiration(units::second_t expirationTime) {
std::scoped_lock lock(m_thisMutex);
m_expiration = expirationTime;
}
double MotorSafety::GetExpiration() const {
units::second_t MotorSafety::GetExpiration() const {
std::scoped_lock lock(m_thisMutex);
return m_expiration;
}
@@ -74,7 +74,7 @@ bool MotorSafety::IsSafetyEnabled() const {
void MotorSafety::Check() {
bool enabled;
double stopTime;
units::second_t stopTime;
{
std::scoped_lock lock(m_thisMutex);

View File

@@ -151,26 +151,18 @@ void Notifier::SetHandler(std::function<void()> handler) {
m_handler = handler;
}
void Notifier::StartSingle(double delay) {
StartSingle(units::second_t(delay));
}
void Notifier::StartSingle(units::second_t delay) {
std::scoped_lock lock(m_processMutex);
m_periodic = false;
m_period = delay.to<double>();
m_period = delay;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}
void Notifier::StartPeriodic(double period) {
StartPeriodic(units::second_t(period));
}
void Notifier::StartPeriodic(units::second_t period) {
std::scoped_lock lock(m_processMutex);
m_periodic = true;
m_period = period.to<double>();
m_period = period;
m_expirationTime = Timer::GetFPGATimestamp() + m_period;
UpdateAlarm();
}

View File

@@ -307,10 +307,6 @@ int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead,
return val;
}
int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout) {
return ReadAutoReceivedData(buffer, numToRead, units::second_t(timeout));
}
int SPI::GetAutoDroppedCount() {
int32_t status = 0;
int32_t val = HAL_GetSPIAutoDroppedCount(m_port, &status);

View File

@@ -31,7 +31,7 @@ SerialPort::SerialPort(int baudRate, Port port, int dataBits,
FRC_CheckErrorStatus(status, "SetSerialStopBits {}", stopBits);
// Set the default timeout to 5 seconds.
SetTimeout(5.0);
SetTimeout(5_s);
// Don't wait until the buffer is full to transmit.
SetWriteBufferMode(kFlushOnAccess);
@@ -61,7 +61,7 @@ SerialPort::SerialPort(int baudRate, std::string_view portName, Port port,
FRC_CheckErrorStatus(status, "SetSerialStopBits {}", stopBits);
// Set the default timeout to 5 seconds.
SetTimeout(5.0);
SetTimeout(5_s);
// Don't wait until the buffer is full to transmit.
SetWriteBufferMode(kFlushOnAccess);
@@ -122,9 +122,9 @@ int SerialPort::Write(std::string_view buffer) {
return retVal;
}
void SerialPort::SetTimeout(double timeout) {
void SerialPort::SetTimeout(units::second_t timeout) {
int32_t status = 0;
HAL_SetSerialTimeout(m_portHandle, timeout, &status);
HAL_SetSerialTimeout(m_portHandle, timeout.to<double>(), &status);
FRC_CheckErrorStatus(status, "{}", "SetTimeout");
}

View File

@@ -76,10 +76,10 @@ bool Solenoid::IsBlackListed() const {
return (value != 0);
}
void Solenoid::SetPulseDuration(double durationSeconds) {
int32_t durationMS = durationSeconds * 1000;
void Solenoid::SetPulseDuration(units::second_t duration) {
int32_t status = 0;
HAL_SetOneShotDuration(m_solenoidHandle, durationMS, &status);
HAL_SetOneShotDuration(m_solenoidHandle,
units::millisecond_t{duration}.to<int32_t>(), &status);
FRC_CheckErrorStatus(status, "Module {} Channel {}", m_moduleNumber,
m_channel);
}

View File

@@ -71,7 +71,7 @@ void TimedRobot::EndCompetition() {
TimedRobot::TimedRobot(double period) : TimedRobot(units::second_t(period)) {}
TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) {
m_startTime = frc2::Timer::GetFPGATimestamp();
m_startTime = Timer::GetFPGATimestamp();
AddPeriodic([=] { LoopFunc(); }, period);
int32_t status = 0;

View File

@@ -4,16 +4,27 @@
#include "frc/Timer.h"
#include <units/time.h>
#include <chrono>
#include <thread>
#include "frc/DriverStation.h"
#include "frc/RobotController.h"
namespace frc {
void Wait(double seconds) {
frc2::Wait(units::second_t(seconds));
void Wait(units::second_t seconds) {
std::this_thread::sleep_for(
std::chrono::duration<double>(seconds.to<double>()));
}
double GetTime() {
return frc2::GetTime().to<double>();
units::second_t GetTime() {
using std::chrono::duration;
using std::chrono::duration_cast;
using std::chrono::system_clock;
return units::second_t(
duration_cast<duration<double>>(system_clock::now().time_since_epoch())
.count());
}
} // namespace frc
@@ -24,30 +35,57 @@ Timer::Timer() {
Reset();
}
double Timer::Get() const {
return m_timer.Get().to<double>();
units::second_t Timer::Get() const {
if (m_running) {
return (GetFPGATimestamp() - m_startTime) + m_accumulatedTime;
} else {
return m_accumulatedTime;
}
}
void Timer::Reset() {
m_timer.Reset();
m_accumulatedTime = 0_s;
m_startTime = GetFPGATimestamp();
}
void Timer::Start() {
m_timer.Start();
if (!m_running) {
m_startTime = GetFPGATimestamp();
m_running = true;
}
}
void Timer::Stop() {
m_timer.Stop();
if (m_running) {
m_accumulatedTime = Get();
m_running = false;
}
}
bool Timer::HasPeriodPassed(double period) {
return m_timer.HasPeriodPassed(units::second_t(period));
bool Timer::HasElapsed(units::second_t period) const {
return Get() > period;
}
double Timer::GetFPGATimestamp() {
return frc2::Timer::GetFPGATimestamp().to<double>();
bool Timer::HasPeriodPassed(units::second_t period) {
return AdvanceIfElapsed(period);
}
double Timer::GetMatchTime() {
return frc2::Timer::GetMatchTime().to<double>();
bool Timer::AdvanceIfElapsed(units::second_t period) {
if (Get() > period) {
// Advance the start time by the period.
m_startTime += period;
// Don't set it to the current time... we want to avoid drift.
return true;
} else {
return false;
}
}
units::second_t Timer::GetFPGATimestamp() {
// FPGA returns the timestamp in microseconds
return units::second_t(frc::RobotController::GetFPGATime() * 1.0e-6);
}
units::second_t Timer::GetMatchTime() {
return units::second_t(frc::DriverStation::GetInstance().GetMatchTime());
}

View File

@@ -142,14 +142,16 @@ double Ultrasonic::GetRangeInches() const {
if (m_simRange) {
return m_simRange.Get();
}
return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
return units::inch_t{m_counter.GetPeriod() * kSpeedOfSound / 2.0}
.to<double>();
} else {
return 0;
}
}
double Ultrasonic::GetRangeMM() const {
return GetRangeInches() * 25.4;
return units::millimeter_t{m_counter.GetPeriod() * kSpeedOfSound / 2.0}
.to<double>();
}
bool Ultrasonic::IsEnabled() const {
@@ -180,7 +182,7 @@ void Ultrasonic::Initialize() {
// Link this instance on the list
m_sensors.emplace_back(this);
m_counter.SetMaxPeriod(1.0);
m_counter.SetMaxPeriod(1_s);
m_counter.SetSemiPeriodMode(true);
m_counter.Reset();
m_enabled = true; // Make it available for round robin scheduling
@@ -204,7 +206,7 @@ void Ultrasonic::UltrasonicChecker() {
sensor->m_pingChannel->Pulse(kPingTime); // do the ping
}
Wait(0.1); // wait for ping to return
Wait(100_ms); // wait for ping to return
}
}
}

View File

@@ -14,7 +14,7 @@
#include <wpi/priority_queue.h>
#include "frc/Errors.h"
#include "frc2/Timer.h"
#include "frc/Timer.h"
using namespace frc;
@@ -131,9 +131,6 @@ void Watchdog::Impl::Main() {
}
}
Watchdog::Watchdog(double timeout, std::function<void()> callback)
: Watchdog(units::second_t{timeout}, callback) {}
Watchdog::Watchdog(units::second_t timeout, std::function<void()> callback)
: m_timeout(timeout), m_callback(std::move(callback)), m_impl(GetImpl()) {}
@@ -167,16 +164,12 @@ Watchdog& Watchdog::operator=(Watchdog&& rhs) {
return *this;
}
double Watchdog::GetTime() const {
return (frc2::Timer::GetFPGATimestamp() - m_startTime).to<double>();
}
void Watchdog::SetTimeout(double timeout) {
SetTimeout(units::second_t{timeout});
units::second_t Watchdog::GetTime() const {
return Timer::GetFPGATimestamp() - m_startTime;
}
void Watchdog::SetTimeout(units::second_t timeout) {
m_startTime = frc2::Timer::GetFPGATimestamp();
m_startTime = Timer::GetFPGATimestamp();
m_tracer.ClearEpochs();
std::scoped_lock lock(m_impl->m_mutex);
@@ -189,9 +182,9 @@ void Watchdog::SetTimeout(units::second_t timeout) {
m_impl->UpdateAlarm();
}
double Watchdog::GetTimeout() const {
units::second_t Watchdog::GetTimeout() const {
std::scoped_lock lock(m_impl->m_mutex);
return m_timeout.to<double>();
return m_timeout;
}
bool Watchdog::IsExpired() const {
@@ -212,7 +205,7 @@ void Watchdog::Reset() {
}
void Watchdog::Enable() {
m_startTime = frc2::Timer::GetFPGATimestamp();
m_startTime = Timer::GetFPGATimestamp();
m_tracer.ClearEpochs();
std::scoped_lock lock(m_impl->m_mutex);

View File

@@ -1,133 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "frc2/Timer.h"
#include <chrono>
#include <thread>
#include "frc/DriverStation.h"
#include "frc/RobotController.h"
namespace frc2 {
void Wait(units::second_t seconds) {
std::this_thread::sleep_for(
std::chrono::duration<double>(seconds.to<double>()));
}
units::second_t GetTime() {
using std::chrono::duration;
using std::chrono::duration_cast;
using std::chrono::system_clock;
return units::second_t(
duration_cast<duration<double>>(system_clock::now().time_since_epoch())
.count());
}
} // namespace frc2
using namespace frc2;
Timer::Timer() {
Reset();
}
Timer::Timer(const Timer& rhs)
: m_startTime(rhs.m_startTime),
m_accumulatedTime(rhs.m_accumulatedTime),
m_running(rhs.m_running) {}
Timer& Timer::operator=(const Timer& rhs) {
std::scoped_lock lock(m_mutex, rhs.m_mutex);
m_startTime = rhs.m_startTime;
m_accumulatedTime = rhs.m_accumulatedTime;
m_running = rhs.m_running;
return *this;
}
Timer::Timer(Timer&& rhs)
: m_startTime(std::move(rhs.m_startTime)),
m_accumulatedTime(std::move(rhs.m_accumulatedTime)),
m_running(std::move(rhs.m_running)) {}
Timer& Timer::operator=(Timer&& rhs) {
std::scoped_lock lock(m_mutex, rhs.m_mutex);
m_startTime = std::move(rhs.m_startTime);
m_accumulatedTime = std::move(rhs.m_accumulatedTime);
m_running = std::move(rhs.m_running);
return *this;
}
units::second_t Timer::Get() const {
units::second_t result;
units::second_t currentTime = GetFPGATimestamp();
std::scoped_lock lock(m_mutex);
if (m_running) {
result = (currentTime - m_startTime) + m_accumulatedTime;
} else {
result = m_accumulatedTime;
}
return result;
}
void Timer::Reset() {
std::scoped_lock lock(m_mutex);
m_accumulatedTime = 0_s;
m_startTime = GetFPGATimestamp();
}
void Timer::Start() {
std::scoped_lock lock(m_mutex);
if (!m_running) {
m_startTime = GetFPGATimestamp();
m_running = true;
}
}
void Timer::Stop() {
units::second_t temp = Get();
std::scoped_lock lock(m_mutex);
if (m_running) {
m_accumulatedTime = temp;
m_running = false;
}
}
bool Timer::HasElapsed(units::second_t period) const {
return Get() > period;
}
bool Timer::HasPeriodPassed(units::second_t period) {
return AdvanceIfElapsed(period);
}
bool Timer::AdvanceIfElapsed(units::second_t period) {
if (Get() > period) {
std::scoped_lock lock(m_mutex);
// Advance the start time by the period.
m_startTime += period;
// Don't set it to the current time... we want to avoid drift.
return true;
} else {
return false;
}
}
units::second_t Timer::GetFPGATimestamp() {
// FPGA returns the timestamp in microseconds
return units::second_t(frc::RobotController::GetFPGATime() * 1.0e-6);
}
units::second_t Timer::GetMatchTime() {
return units::second_t(frc::DriverStation::GetInstance().GetMatchTime());
}

View File

@@ -17,7 +17,7 @@ NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
auto& registry = SendableRegistry::GetInstance();
registry.AddChild(this, &m_dio);
registry.AddChild(this, &m_pwm);
SetExpiration(0.0);
SetExpiration(0_s);
SetSafetyEnabled(false);
// the dio controls the output (in PWM mode)

View File

@@ -7,6 +7,7 @@
#include <memory>
#include <hal/Types.h>
#include <units/time.h>
#include "frc/AnalogTrigger.h"
#include "frc/CounterBase.h"
@@ -368,7 +369,7 @@ class Counter : public CounterBase,
*
* @returns The period between the last two pulses in units of seconds.
*/
double GetPeriod() const override;
units::second_t GetPeriod() const override;
/**
* Set the maximum period where the device is still considered "moving".
@@ -380,7 +381,7 @@ class Counter : public CounterBase,
* @param maxPeriod The maximum period where the counted device is considered
* moving in seconds.
*/
void SetMaxPeriod(double maxPeriod) final;
void SetMaxPeriod(units::second_t maxPeriod) final;
/**
* Select whether you want to continue updating the event timer output when

View File

@@ -4,6 +4,8 @@
#pragma once
#include <units/time.h>
namespace frc {
/**
@@ -27,8 +29,8 @@ class CounterBase {
virtual int Get() const = 0;
virtual void Reset() = 0;
virtual double GetPeriod() const = 0;
virtual void SetMaxPeriod(double maxPeriod) = 0;
virtual units::second_t GetPeriod() const = 0;
virtual void SetMaxPeriod(units::second_t maxPeriod) = 0;
virtual bool GetStopped() const = 0;
virtual bool GetDirection() const = 0;
};

View File

@@ -12,6 +12,7 @@
#include <fmt/format.h>
#include <hal/DriverStationTypes.h>
#include <units/time.h>
#include <wpi/condition_variable.h>
#include <wpi/mutex.h>
@@ -334,11 +335,11 @@ class DriverStation {
* This is a good way to delay processing until there is new driver station
* data to act on.
*
* @param timeout Timeout time in seconds
* @param timeout Timeout
*
* @return true if new data, otherwise false
*/
bool WaitForData(double timeout);
bool WaitForData(units::second_t timeout);
/**
* Return the approximate match time.
@@ -494,7 +495,7 @@ class DriverStation {
bool m_userInTeleop = false;
bool m_userInTest = false;
double m_nextMessageTime = 0;
units::second_t m_nextMessageTime = 0_s;
};
} // namespace frc

View File

@@ -167,7 +167,7 @@ class Encoder : public CounterBase,
*
* @return Period in seconds of the most recent pulse.
*/
double GetPeriod() const override;
units::second_t GetPeriod() const override;
/**
* Sets the maximum period for stopped detection.
@@ -188,7 +188,7 @@ class Encoder : public CounterBase,
WPI_DEPRECATED(
"Use SetMinRate() in favor of this method. This takes unscaled periods "
"and SetMinRate() scales using value from SetDistancePerPulse().")
void SetMaxPeriod(double maxPeriod) override;
void SetMaxPeriod(units::second_t maxPeriod) override;
/**
* Determine if the encoder is stopped.

View File

@@ -8,6 +8,7 @@
#include <memory>
#include <hal/Interrupts.h>
#include <units/time.h>
#include "frc/AnalogTriggerType.h"
@@ -86,12 +87,12 @@ class InterruptableSensorBase {
* waiting for an interrupt. This is not threadsafe, and can cause memory
* corruption
*
* @param timeout Timeout in seconds
* @param timeout Timeout
* @param ignorePrevious If true, ignore interrupts that happened before
* WaitForInterrupt was called.
* @return What interrupts fired
*/
virtual WaitResult WaitForInterrupt(double timeout,
virtual WaitResult WaitForInterrupt(units::second_t timeout,
bool ignorePrevious = true);
/**
@@ -116,7 +117,7 @@ class InterruptableSensorBase {
*
* @return Timestamp in seconds since boot.
*/
virtual double ReadRisingTimestamp();
virtual units::second_t ReadRisingTimestamp();
/**
* Return the timestamp for the falling interrupt that occurred most recently.
@@ -127,7 +128,7 @@ class InterruptableSensorBase {
*
* @return Timestamp in seconds since boot.
*/
virtual double ReadFallingTimestamp();
virtual units::second_t ReadFallingTimestamp();
/**
* Set which edge to trigger interrupts on

View File

@@ -6,6 +6,7 @@
#include <string>
#include <units/time.h>
#include <wpi/mutex.h>
#include "frc/Timer.h"
@@ -36,16 +37,16 @@ class MotorSafety {
/**
* Set the expiration time for the corresponding motor safety object.
*
* @param expirationTime The timeout value in seconds.
* @param expirationTime The timeout value.
*/
void SetExpiration(double expirationTime);
void SetExpiration(units::second_t expirationTime);
/**
* Retrieve the timeout value for the corresponding motor safety object.
*
* @return the timeout value in seconds.
* @return the timeout value.
*/
double GetExpiration() const;
units::second_t GetExpiration() const;
/**
* Determine if the motor is still operating or has timed out.
@@ -93,16 +94,16 @@ class MotorSafety {
virtual std::string GetDescription() const = 0;
private:
static constexpr double kDefaultSafetyExpiration = 0.1;
static constexpr auto kDefaultSafetyExpiration = 100_ms;
// The expiration time for this object
double m_expiration = kDefaultSafetyExpiration;
units::second_t m_expiration = kDefaultSafetyExpiration;
// True if motor safety is enabled for this motor
bool m_enabled = false;
// The FPGA clock value when the motor has expired
double m_stopTime = Timer::GetFPGATimestamp();
units::second_t m_stopTime = Timer::GetFPGATimestamp();
mutable wpi::mutex m_thisMutex;
};

View File

@@ -15,7 +15,6 @@
#include <hal/Types.h>
#include <units/time.h>
#include <wpi/deprecated.h>
#include <wpi/mutex.h>
namespace frc {
@@ -80,19 +79,6 @@ class Notifier {
*/
void SetHandler(std::function<void()> handler);
/**
* Register for single event notification.
*
* A timer event is queued for a single event after the specified delay.
*
* @deprecated Use unit-safe StartSingle(units::second_t delay) method
* instead.
*
* @param delay Seconds to wait before the handler is called.
*/
WPI_DEPRECATED("Use unit-safe StartSingle method instead.")
void StartSingle(double delay);
/**
* Register for single event notification.
*
@@ -102,22 +88,6 @@ class Notifier {
*/
void StartSingle(units::second_t delay);
/**
* Register for periodic event notification.
*
* A timer event is queued for periodic event notification. Each time the
* interrupt occurs, the event will be immediately requeued for the same time
* interval.
*
* @deprecated Use unit-safe StartPeriodic(units::second_t period) method
* instead
*
* @param period Period in seconds to call the handler starting one period
* after the call to this method.
*/
WPI_DEPRECATED("Use unit-safe StartPeriodic method instead.")
void StartPeriodic(double period);
/**
* Register for periodic event notification.
*
@@ -184,10 +154,10 @@ class Notifier {
std::function<void()> m_handler;
// The absolute expiration time
double m_expirationTime = 0;
units::second_t m_expirationTime = 0_s;
// The relative time (either periodic or single)
double m_period = 0;
units::second_t m_period = 0_s;
// True if this is a periodic event
bool m_periodic = false;

View File

@@ -242,32 +242,6 @@ class SPI {
int ReadAutoReceivedData(uint32_t* buffer, int numToRead,
units::second_t timeout);
/**
* Read data that has been transferred by the automatic SPI transfer engine.
*
* Transfers may be made a byte at a time, so it's necessary for the caller
* to handle cases where an entire transfer has not been completed.
*
* Each received data sequence consists of a timestamp followed by the
* received data bytes, one byte per word (in the least significant byte).
* The length of each received data sequence is the same as the combined
* size of the data and zeroSize set in SetAutoTransmitData().
*
* Blocks until numToRead words have been read or timeout expires.
* May be called with numToRead=0 to retrieve how many words are available.
*
* @deprecated Use unit safe version instead.
* ReadAutoReceivedData(uint32_t* buffer, int numToRead, <!--
* --> units::second_t timeout)
*
* @param buffer buffer where read words are stored
* @param numToRead number of words to read
* @param timeout timeout in seconds (ms resolution)
* @return Number of words remaining to be read
*/
WPI_DEPRECATED("Use ReadAutoReceivedData with unit-safety instead")
int ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout);
/**
* Get the number of bytes dropped by the automatic SPI transfer engine due
* to the receive buffer being full.

View File

@@ -8,7 +8,7 @@
#include <string_view>
#include <hal/Types.h>
#include <wpi/deprecated.h>
#include <units/time.h>
namespace frc {
@@ -155,9 +155,9 @@ class SerialPort {
* This defines the timeout for transactions with the hardware.
* It will affect reads and very large writes.
*
* @param timeout The number of seconds to to wait for I/O.
* @param timeout The time to wait for I/O.
*/
void SetTimeout(double timeout);
void SetTimeout(units::second_t timeout);
/**
* Specify the size of the input buffer.

View File

@@ -4,12 +4,12 @@
#pragma once
#include <frc2/Timer.h>
#include <algorithm>
#include <units/time.h>
#include "frc/Timer.h"
namespace frc {
/**
* A class that limits the rate of change of an input value. Useful for
@@ -36,7 +36,7 @@ class SlewRateLimiter {
explicit SlewRateLimiter(Rate_t rateLimit, Unit_t initialValue = Unit_t{0})
: m_rateLimit{rateLimit},
m_prevVal{initialValue},
m_prevTime{frc2::Timer::GetFPGATimestamp()} {}
m_prevTime{Timer::GetFPGATimestamp()} {}
/**
* Filters the input to limit its slew rate.
@@ -46,7 +46,7 @@ class SlewRateLimiter {
* rate.
*/
Unit_t Calculate(Unit_t input) {
units::second_t currentTime = frc2::Timer::GetFPGATimestamp();
units::second_t currentTime = Timer::GetFPGATimestamp();
units::second_t elapsedTime = currentTime - m_prevTime;
m_prevVal += std::clamp(input - m_prevVal, -m_rateLimit * elapsedTime,
m_rateLimit * elapsedTime);
@@ -62,7 +62,7 @@ class SlewRateLimiter {
*/
void Reset(Unit_t value) {
m_prevVal = value;
m_prevTime = frc2::Timer::GetFPGATimestamp();
m_prevTime = Timer::GetFPGATimestamp();
}
private:

View File

@@ -5,6 +5,7 @@
#pragma once
#include <hal/Types.h>
#include <units/time.h>
#include "frc/SolenoidBase.h"
#include "frc/smartdashboard/Sendable.h"
@@ -93,7 +94,7 @@ class Solenoid : public SolenoidBase,
*
* @see startPulse()
*/
void SetPulseDuration(double durationSeconds);
void SetPulseDuration(units::second_t duration);
/**
* Trigger the PCM to generate a pulse of the duration set in

View File

@@ -15,7 +15,7 @@
#include <wpi/priority_queue.h>
#include "frc/IterativeRobotBase.h"
#include "frc2/Timer.h"
#include "frc/Timer.h"
namespace frc {
@@ -30,7 +30,7 @@ namespace frc {
*/
class TimedRobot : public IterativeRobotBase {
public:
static constexpr units::second_t kDefaultPeriod = 20_ms;
static constexpr auto kDefaultPeriod = 20_ms;
/**
* Provide an alternate "main loop" via StartCompetition().
@@ -99,12 +99,11 @@ class TimedRobot : public IterativeRobotBase {
units::second_t period, units::second_t offset)
: func{std::move(func)},
period{period},
expirationTime{
startTime + offset +
units::math::floor((frc2::Timer::GetFPGATimestamp() - startTime) /
period) *
period +
period} {}
expirationTime{startTime + offset +
units::math::floor(
(Timer::GetFPGATimestamp() - startTime) / period) *
period +
period} {}
bool operator>(const Callback& rhs) const {
return expirationTime > rhs.expirationTime;

View File

@@ -4,7 +4,7 @@
#pragma once
#include "frc2/Timer.h"
#include <units/time.h>
namespace frc {
@@ -18,23 +18,17 @@ namespace frc {
*
* @param seconds Length of time to pause, in seconds.
*/
void Wait(double seconds);
void Wait(units::second_t seconds);
/**
* @brief Gives real-time clock system time with nanosecond resolution
* @return The time, just in case you want the robot to start autonomous at 8pm
* on Saturday.
*/
double GetTime();
units::second_t GetTime();
/**
* Timer objects measure accumulated time in seconds.
*
* The timer object functions like a stopwatch. It can be started, stopped, and
* cleared. When the timer is running its value counts up in seconds. When
* stopped, the timer holds the current value. The implementation simply records
* the time when started and subtracts the current time whenever the value is
* requested.
* A wrapper for the frc::Timer class that returns unit-typed values.
*/
class Timer {
public:
@@ -48,10 +42,10 @@ class Timer {
virtual ~Timer() = default;
Timer(const Timer& rhs) = default;
Timer& operator=(const Timer& rhs) = default;
Timer(Timer&& rhs) = default;
Timer& operator=(Timer&& rhs) = default;
Timer(const Timer&) = default;
Timer& operator=(const Timer&) = default;
Timer(Timer&&) = default;
Timer& operator=(Timer&&) = default;
/**
* Get the current time from the timer. If the clock is running it is derived
@@ -60,7 +54,7 @@ class Timer {
*
* @return Current time value for this timer in seconds
*/
double Get() const;
units::second_t Get() const;
/**
* Reset the timer by setting the time to 0.
@@ -74,7 +68,8 @@ class Timer {
* Start the timer running.
*
* Just set the running flag to true indicating that all time requests should
* be relative to the system clock.
* be relative to the system clock. Note that this method is a no-op if the
* timer is already running.
*/
void Start();
@@ -87,15 +82,33 @@ class Timer {
*/
void Stop();
/**
* Check if the period specified has passed.
*
* @param seconds The period to check.
* @return True if the period has passed.
*/
bool HasElapsed(units::second_t period) const;
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for (in seconds).
* @param period The period to check for.
* @return True if the period has passed.
*/
bool HasPeriodPassed(double period);
bool HasPeriodPassed(units::second_t period);
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for.
* @return True if the period has passed.
*/
bool AdvanceIfElapsed(units::second_t period);
/**
* Return the FPGA system clock time in seconds.
@@ -105,7 +118,7 @@ class Timer {
*
* @returns Robot running time in seconds.
*/
static double GetFPGATimestamp();
static units::second_t GetFPGATimestamp();
/**
* Return the approximate match time.
@@ -122,10 +135,12 @@ class Timer {
*
* @return Time remaining in current match period (auto or teleop)
*/
static double GetMatchTime();
static units::second_t GetMatchTime();
private:
frc2::Timer m_timer;
units::second_t m_startTime = 0_s;
units::second_t m_accumulatedTime = 0_s;
bool m_running = false;
};
} // namespace frc

View File

@@ -10,6 +10,8 @@
#include <vector>
#include <hal/SimDevice.h>
#include <units/time.h>
#include <units/velocity.h>
#include "frc/Counter.h"
#include "frc/smartdashboard/Sendable.h"
@@ -174,8 +176,8 @@ class Ultrasonic : public Sendable, public SendableHelper<Ultrasonic> {
static constexpr int kPriority = 64;
// Max time (ms) between readings.
static constexpr double kMaxUltrasonicTime = 0.1;
static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
static constexpr auto kMaxUltrasonicTime = 0.1_s;
static constexpr auto kSpeedOfSound = 1130_fps;
// Thread doing the round-robin automatic sensing
static std::thread m_thread;

View File

@@ -9,7 +9,6 @@
#include <units/time.h>
#include <wpi/StringRef.h>
#include <wpi/deprecated.h>
#include "frc/Tracer.h"
@@ -26,19 +25,6 @@ namespace frc {
*/
class Watchdog {
public:
/**
* Watchdog constructor.
*
* @deprecated use unit-safe version instead.
* Watchdog(units::second_t timeout, std::function<void()> callback)
*
* @param timeout The watchdog's timeout in seconds with microsecond
* resolution.
* @param callback This function is called when the timeout expires.
*/
WPI_DEPRECATED("Use unit-safe version instead")
Watchdog(double timeout, std::function<void()> callback);
/**
* Watchdog constructor.
*
@@ -48,11 +34,6 @@ class Watchdog {
*/
Watchdog(units::second_t timeout, std::function<void()> callback);
template <typename Callable, typename Arg, typename... Args>
WPI_DEPRECATED("Use unit-safe version instead")
Watchdog(double timeout, Callable&& f, Arg&& arg, Args&&... args)
: Watchdog(units::second_t{timeout}, arg, args...) {}
template <typename Callable, typename Arg, typename... Args>
Watchdog(units::second_t timeout, Callable&& f, Arg&& arg, Args&&... args)
: Watchdog(timeout,
@@ -65,21 +46,9 @@ class Watchdog {
Watchdog& operator=(Watchdog&& rhs);
/**
* Returns the time in seconds since the watchdog was last fed.
* Returns the time since the watchdog was last fed.
*/
double GetTime() const;
/**
* Sets the watchdog's timeout.
*
* @deprecated use the unit safe version instead.
* SetTimeout(units::second_t timeout)
*
* @param timeout The watchdog's timeout in seconds with microsecond
* resolution.
*/
WPI_DEPRECATED("Use unit-safe version instead")
void SetTimeout(double timeout);
units::second_t GetTime() const;
/**
* Sets the watchdog's timeout.
@@ -90,9 +59,9 @@ class Watchdog {
void SetTimeout(units::second_t timeout);
/**
* Returns the watchdog's timeout in seconds.
* Returns the watchdog's timeout.
*/
double GetTimeout() const;
units::second_t GetTimeout() const;
/**
* Returns true if the watchdog timer has expired.
@@ -143,7 +112,7 @@ class Watchdog {
private:
// Used for timeout print rate-limiting
static constexpr units::second_t kMinPrintPeriod = 1_s;
static constexpr auto kMinPrintPeriod = 1_s;
units::second_t m_startTime = 0_s;
units::second_t m_timeout;

View File

@@ -1,148 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <units/time.h>
#include <wpi/mutex.h>
namespace frc2 {
/**
* Pause the task for a specified time.
*
* Pause the execution of the program for a specified period of time given in
* seconds. Motors will continue to run at their last assigned values, and
* sensors will continue to update. Only the task containing the wait will pause
* until the wait time is expired.
*
* @param seconds Length of time to pause, in seconds.
*/
void Wait(units::second_t seconds);
/**
* @brief Gives real-time clock system time with nanosecond resolution
* @return The time, just in case you want the robot to start autonomous at 8pm
* on Saturday.
*/
units::second_t GetTime();
/**
* A wrapper for the frc::Timer class that returns unit-typed values.
*/
class Timer {
public:
/**
* Create a new timer object.
*
* Create a new timer object and reset the time to zero. The timer is
* initially not running and must be started.
*/
Timer();
virtual ~Timer() = default;
Timer(const Timer& rhs);
Timer& operator=(const Timer& rhs);
Timer(Timer&& rhs);
Timer& operator=(Timer&& rhs);
/**
* Get the current time from the timer. If the clock is running it is derived
* from the current system clock the start time stored in the timer class. If
* the clock is not running, then return the time when it was last stopped.
*
* @return Current time value for this timer in seconds
*/
units::second_t Get() const;
/**
* Reset the timer by setting the time to 0.
*
* Make the timer startTime the current time so new requests will be relative
* to now.
*/
void Reset();
/**
* Start the timer running.
*
* Just set the running flag to true indicating that all time requests should
* be relative to the system clock. Note that this method is a no-op if the
* timer is already running.
*/
void Start();
/**
* Stop the timer.
*
* This computes the time as of now and clears the running flag, causing all
* subsequent time requests to be read from the accumulated time rather than
* looking at the system clock.
*/
void Stop();
/**
* Check if the period specified has passed.
*
* @param seconds The period to check.
* @return True if the period has passed.
*/
bool HasElapsed(units::second_t period) const;
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for.
* @return True if the period has passed.
*/
bool HasPeriodPassed(units::second_t period);
/**
* Check if the period specified has passed and if it has, advance the start
* time by that period. This is useful to decide if it's time to do periodic
* work without drifting later by the time it took to get around to checking.
*
* @param period The period to check for.
* @return True if the period has passed.
*/
bool AdvanceIfElapsed(units::second_t period);
/**
* Return the FPGA system clock time in seconds.
*
* Return the time from the FPGA hardware clock in seconds since the FPGA
* started. Rolls over after 71 minutes.
*
* @returns Robot running time in seconds.
*/
static units::second_t GetFPGATimestamp();
/**
* Return the approximate match time.
*
* The FMS does not send an official match time to the robots, but does send
* an approximate match time. The value will count down the time remaining in
* the current period (auto or teleop).
*
* Warning: This is not an official time (so it cannot be used to dispute ref
* calls or guarantee that a function will trigger before the match ends).
*
* The Practice Match function of the DS approximates the behavior seen on the
* field.
*
* @return Time remaining in current match period (auto or teleop)
*/
static units::second_t GetMatchTime();
private:
units::second_t m_startTime = 0_s;
units::second_t m_accumulatedTime = 0_s;
bool m_running = false;
mutable wpi::mutex m_mutex;
};
} // namespace frc2

View File

@@ -75,7 +75,7 @@ TEST_F(WatchdogTest, SetTimeout) {
frc::sim::StepTiming(0.2_s);
watchdog.SetTimeout(0.2_s);
EXPECT_EQ(0.2, watchdog.GetTimeout());
EXPECT_EQ(0.2_s, watchdog.GetTimeout());
EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
frc::sim::StepTiming(0.3_s);

View File

@@ -4,7 +4,7 @@
#include "ReplaceMeTimedCommand.h"
ReplaceMeTimedCommand::ReplaceMeTimedCommand(double timeout)
ReplaceMeTimedCommand::ReplaceMeTimedCommand(units::second_t timeout)
: TimedCommand(timeout) {
// Use Requires() here to declare subsystem dependencies
// eg. Requires(Robot::chassis.get());

View File

@@ -5,10 +5,11 @@
#pragma once
#include <frc/commands/TimedCommand.h>
#include <units/time.h>
class ReplaceMeTimedCommand : public frc::TimedCommand {
public:
explicit ReplaceMeTimedCommand(double timeout);
explicit ReplaceMeTimedCommand(units::second_t timeout);
void Initialize() override;
void Execute() override;
void End() override;

View File

@@ -4,7 +4,7 @@
#include "Drivetrain.h"
#include <frc2/Timer.h>
#include <frc/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
@@ -38,5 +38,5 @@ void Drivetrain::UpdateOdometry() {
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
frc::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -12,7 +12,7 @@
class Robot : public frc::TimedRobot {
public:
Robot() {
m_robotDrive.SetExpiration(0.1);
m_robotDrive.SetExpiration(100_ms);
m_timer.Start();
}
@@ -23,7 +23,7 @@ class Robot : public frc::TimedRobot {
void AutonomousPeriodic() override {
// Drive for 2 seconds
if (m_timer.Get() < 2.0) {
if (m_timer.Get() < 2_s) {
// Drive forwards half speed
m_robotDrive.ArcadeDrive(0.5, 0.0);
} else {

View File

@@ -4,7 +4,7 @@
#include "Drivetrain.h"
#include <frc2/Timer.h>
#include <frc/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
@@ -58,5 +58,5 @@ void Drivetrain::UpdateOdometry() {
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
frc::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -6,7 +6,7 @@
#include "Robot.h"
CheckForHotGoal::CheckForHotGoal(double time) {
CheckForHotGoal::CheckForHotGoal(units::second_t time) {
SetTimeout(time);
}

View File

@@ -14,10 +14,10 @@
DriveAndShootAutonomous::DriveAndShootAutonomous() {
AddSequential(new CloseClaw());
AddSequential(new WaitForPressure(), 2);
AddSequential(new WaitForPressure(), 2_s);
#ifndef SIMULATION
// NOTE: Simulation doesn't currently have the concept of hot.
AddSequential(new CheckForHotGoal(2));
AddSequential(new CheckForHotGoal(2_s));
#endif
AddSequential(new SetPivotSetpoint(45));
AddSequential(new DriveForward(8, 0.3));

View File

@@ -29,7 +29,7 @@ DriveForward::DriveForward(double dist, double maxSpeed) {
// Called just before this Command runs the first time
void DriveForward::Initialize() {
Robot::drivetrain.GetRightEncoder().Reset();
SetTimeout(2);
SetTimeout(2_s);
}
// Called repeatedly when this Command is scheduled to run

View File

@@ -6,7 +6,7 @@
#include "Robot.h"
ExtendShooter::ExtendShooter() : frc::TimedCommand(1.0) {
ExtendShooter::ExtendShooter() : frc::TimedCommand(1_s) {
Requires(&Robot::shooter);
}

View File

@@ -19,7 +19,7 @@ DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
// Configure the DifferentialDrive to reflect the fact that all our
// motors are wired backwards and our drivers sensitivity preferences.
m_robotDrive.SetSafetyEnabled(false);
m_robotDrive.SetExpiration(0.1);
m_robotDrive.SetExpiration(100_ms);
m_robotDrive.SetMaxOutput(1.0);
m_leftCIMs.SetInverted(true);
m_rightCIMs.SetInverted(true);

View File

@@ -5,6 +5,7 @@
#pragma once
#include <frc/commands/Command.h>
#include <units/time.h>
/**
* This command looks for the hot goal and waits until it's detected or timed
@@ -14,6 +15,6 @@
*/
class CheckForHotGoal : public frc::Command {
public:
explicit CheckForHotGoal(double time);
explicit CheckForHotGoal(units::second_t time);
bool IsFinished() override;
};

View File

@@ -4,12 +4,12 @@
#include <frc/SlewRateLimiter.h>
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/controller/RamseteController.h>
#include <frc/smartdashboard/Field2d.h>
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc2/Timer.h>
#include "Drivetrain.h"
@@ -89,7 +89,7 @@ class Robot : public frc::TimedRobot {
frc::RamseteController m_ramseteController;
// The timer to use during the autonomous period.
frc2::Timer m_timer;
frc::Timer m_timer;
// Create Field2d for robot and trajectory visualizations.
frc::Field2d m_field;

View File

@@ -7,7 +7,7 @@
#include <frc/DigitalInput.h>
#include <frc/DigitalOutput.h>
#include <frc/Errors.h>
#include <frc2/Timer.h>
#include <frc/Timer.h>
OnBoardIO::OnBoardIO(OnBoardIO::ChannelMode dio1, OnBoardIO::ChannelMode dio2) {
if (dio1 == ChannelMode::INPUT) {
@@ -30,7 +30,7 @@ bool OnBoardIO::GetButtonBPressed() {
return m_buttonB->Get();
}
auto currentTime = frc2::Timer::GetFPGATimestamp();
auto currentTime = frc::Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
FRC_ReportError(frc::err::Error, "Button {} was not configured", "B");
m_nextMessageTime = currentTime + kMessageInterval;
@@ -43,7 +43,7 @@ bool OnBoardIO::GetButtonCPressed() {
return m_buttonC->Get();
}
auto currentTime = frc2::Timer::GetFPGATimestamp();
auto currentTime = frc::Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
FRC_ReportError(frc::err::Error, "Button {} was not configured", "C");
m_nextMessageTime = currentTime + kMessageInterval;
@@ -55,7 +55,7 @@ void OnBoardIO::SetGreenLed(bool value) {
if (m_greenLed) {
m_greenLed->Set(value);
} else {
auto currentTime = frc2::Timer::GetFPGATimestamp();
auto currentTime = frc::Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
FRC_ReportError(frc::err::Error, "{} LED was not configured", "Green");
m_nextMessageTime = currentTime + kMessageInterval;
@@ -67,7 +67,7 @@ void OnBoardIO::SetRedLed(bool value) {
if (m_redLed) {
m_redLed->Set(value);
} else {
auto currentTime = frc2::Timer::GetFPGATimestamp();
auto currentTime = frc::Timer::GetFPGATimestamp();
if (currentTime > m_nextMessageTime) {
FRC_ReportError(frc::err::Error, "{} LED was not configured", "Red");
m_nextMessageTime = currentTime + kMessageInterval;

View File

@@ -4,7 +4,7 @@
#pragma once
#include <frc2/Timer.h>
#include <frc/Timer.h>
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include <units/time.h>
@@ -27,5 +27,5 @@ class DriveTime : public frc2::CommandHelper<frc2::CommandBase, DriveTime> {
double m_speed;
units::second_t m_duration;
Drivetrain* m_drive;
frc2::Timer m_timer;
frc::Timer m_timer;
};

View File

@@ -4,7 +4,7 @@
#pragma once
#include <frc2/Timer.h>
#include <frc/Timer.h>
#include <frc2/command/CommandBase.h>
#include <frc2/command/CommandHelper.h>
#include <units/time.h>
@@ -27,5 +27,5 @@ class TurnTime : public frc2::CommandHelper<frc2::CommandBase, TurnTime> {
double m_speed;
units::second_t m_duration;
Drivetrain* m_drive;
frc2::Timer m_timer;
frc::Timer m_timer;
};

View File

@@ -4,10 +4,10 @@
#include <frc/SlewRateLimiter.h>
#include <frc/TimedRobot.h>
#include <frc/Timer.h>
#include <frc/XboxController.h>
#include <frc/controller/RamseteController.h>
#include <frc/trajectory/TrajectoryGenerator.h>
#include <frc2/Timer.h>
#include "Drivetrain.h"
@@ -69,7 +69,7 @@ class Robot : public frc::TimedRobot {
Drivetrain m_drive;
frc::Trajectory m_trajectory;
frc::RamseteController m_ramsete;
frc2::Timer m_timer;
frc::Timer m_timer;
};
#ifndef RUNNING_FRC_TESTS

View File

@@ -4,7 +4,7 @@
#include "Drivetrain.h"
#include <frc2/Timer.h>
#include <frc/Timer.h>
#include "ExampleGlobalMeasurementSensor.h"
@@ -37,5 +37,5 @@ void Drivetrain::UpdateOdometry() {
m_poseEstimator.AddVisionMeasurement(
ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
m_poseEstimator.GetEstimatedPosition()),
frc2::Timer::GetFPGATimestamp() - 0.3_s);
frc::Timer::GetFPGATimestamp() - 0.3_s);
}

View File

@@ -2,6 +2,8 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <units/time.h>
#include "TestBench.h"
#include "frc/AnalogInput.h"
#include "frc/AnalogOutput.h"
@@ -12,7 +14,7 @@
using namespace frc;
static const double kDelayTime = 0.01;
static constexpr auto kDelayTime = 10_ms;
/**
* A fixture with an analog input and an analog output wired together

View File

@@ -34,14 +34,14 @@ class AnalogPotentiometerTest : public testing::Test {
TEST_F(AnalogPotentiometerTest, TestInitialSettings) {
m_fakePot->SetVoltage(0.0);
Wait(0.1);
Wait(0.1_s);
EXPECT_NEAR(0.0, m_pot->Get(), 5.0)
<< "The potentiometer did not initialize to 0.";
}
TEST_F(AnalogPotentiometerTest, TestRangeValues) {
m_fakePot->SetVoltage(kAngle / kScale * RobotController::GetVoltage5V());
Wait(0.1);
Wait(0.1_s);
EXPECT_NEAR(kAngle, m_pot->Get(), 2.0)
<< "The potentiometer did not measure the correct angle.";
}

View File

@@ -19,7 +19,7 @@ TEST(BuiltInAccelerometerTest, Accelerometer) {
/* The testbench sometimes shakes a little from a previous test. Give it
some time. */
Wait(1.0);
Wait(1_s);
ASSERT_NEAR(0.0, accelerometer.GetX(), kAccelerationTolerance);
ASSERT_NEAR(1.0, accelerometer.GetY(), kAccelerationTolerance);

View File

@@ -4,6 +4,8 @@
#include "frc/Counter.h" // NOLINT(build/include_order)
#include <units/time.h>
#include "TestBench.h"
#include "frc/Timer.h"
#include "frc/motorcontrol/Jaguar.h"
@@ -13,9 +15,9 @@
using namespace frc;
static const double kMotorDelay = 2.5;
static constexpr auto kMotorDelay = 2.5_s;
static const double kMaxPeriod = 2.0;
static constexpr auto kMaxPeriod = 2_s;
class CounterTest : public testing::Test {
protected:
@@ -63,13 +65,13 @@ TEST_F(CounterTest, CountTalon) {
/* Run the motor forward and determine if the counter is counting. */
m_talon->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_NE(0.0, m_talonCounter->Get()) << "The counter did not count (talon)";
/* Set the motor to 0 and determine if the counter resets to 0. */
m_talon->Set(0.0);
Wait(0.5);
Wait(0.5_s);
m_talonCounter->Reset();
EXPECT_FLOAT_EQ(0.0, m_talonCounter->Get())
@@ -81,14 +83,14 @@ TEST_F(CounterTest, CountVictor) {
/* Run the motor forward and determine if the counter is counting. */
m_victor->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_NE(0.0, m_victorCounter->Get())
<< "The counter did not count (victor)";
/* Set the motor to 0 and determine if the counter resets to 0. */
m_victor->Set(0.0);
Wait(0.5);
Wait(0.5_s);
m_victorCounter->Reset();
EXPECT_FLOAT_EQ(0.0, m_victorCounter->Get())
@@ -100,14 +102,14 @@ TEST_F(CounterTest, CountJaguar) {
/* Run the motor forward and determine if the counter is counting. */
m_jaguar->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_NE(0.0, m_jaguarCounter->Get())
<< "The counter did not count (jaguar)";
/* Set the motor to 0 and determine if the counter resets to 0. */
m_jaguar->Set(0.0);
Wait(0.5);
Wait(0.5_s);
m_jaguarCounter->Reset();
EXPECT_FLOAT_EQ(0.0, m_jaguarCounter->Get())
@@ -124,7 +126,7 @@ TEST_F(CounterTest, TalonGetStopped) {
/* Set the Max Period of the counter and run the motor */
m_talonCounter->SetMaxPeriod(kMaxPeriod);
m_talon->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_FALSE(m_talonCounter->GetStopped()) << "The counter did not count.";
@@ -142,7 +144,7 @@ TEST_F(CounterTest, VictorGetStopped) {
/* Set the Max Period of the counter and run the motor */
m_victorCounter->SetMaxPeriod(kMaxPeriod);
m_victor->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_FALSE(m_victorCounter->GetStopped()) << "The counter did not count.";
@@ -160,7 +162,7 @@ TEST_F(CounterTest, JaguarGetStopped) {
/* Set the Max Period of the counter and run the motor */
m_jaguarCounter->SetMaxPeriod(kMaxPeriod);
m_jaguar->Set(1.0);
Wait(0.5);
Wait(0.5_s);
EXPECT_FALSE(m_jaguarCounter->GetStopped()) << "The counter did not count.";

View File

@@ -6,20 +6,26 @@
#include "frc/DigitalOutput.h" // NOLINT(build/include_order)
#include <units/math.h>
#include <units/time.h>
#include "TestBench.h"
#include "frc/Counter.h"
#include "frc/InterruptableSensorBase.h"
#include "frc/Timer.h"
#include "gtest/gtest.h"
#define EXPECT_NEAR_UNITS(val1, val2, eps) \
EXPECT_LE(units::math::abs(val1 - val2), eps)
using namespace frc;
static const double kCounterTime = 0.001;
static constexpr auto kCounterTime = 1_ms;
static const double kDelayTime = 0.1;
static constexpr auto kDelayTime = 100_ms;
static const double kSynchronousInterruptTime = 2.0;
static const double kSynchronousInterruptTimeTolerance = 0.01;
static constexpr auto kSynchronousInterruptTime = 2_s;
static constexpr auto kSynchronousInterruptTimeTolerance = 10_ms;
/**
* A fixture with a digital input and a digital output physically wired
@@ -75,31 +81,31 @@ TEST_F(DIOLoopTest, DIOPWM) {
m_output->SetPWMRate(2.0);
// Enable PWM, but leave it off
m_output->EnablePWM(0.0);
Wait(0.5);
Wait(0.5_s);
m_output->UpdateDutyCycle(0.5);
m_input->RequestInterrupts();
m_input->SetUpSourceEdge(false, true);
InterruptableSensorBase::WaitResult result =
m_input->WaitForInterrupt(3.0, true);
m_input->WaitForInterrupt(3_s, true);
Wait(0.5);
Wait(0.5_s);
bool firstCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool secondCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool thirdCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool forthCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool fifthCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool sixthCycle = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool seventhCycle = m_input->Get();
m_output->DisablePWM();
Wait(0.5);
Wait(0.5_s);
bool firstAfterStop = m_input->Get();
Wait(0.5);
Wait(0.5_s);
bool secondAfterStop = m_input->Get();
EXPECT_EQ(InterruptableSensorBase::WaitResult::kFallingEdge, result)
@@ -179,7 +185,7 @@ TEST_F(DIOLoopTest, SynchronousInterruptWorks) {
// Then this thread should pause and resume after that number of seconds
Timer timer;
timer.Start();
m_input->WaitForInterrupt(kSynchronousInterruptTime + 1.0);
EXPECT_NEAR(kSynchronousInterruptTime, timer.Get(),
kSynchronousInterruptTimeTolerance);
m_input->WaitForInterrupt(kSynchronousInterruptTime + 1_s);
EXPECT_NEAR_UNITS(kSynchronousInterruptTime, timer.Get(),
kSynchronousInterruptTimeTolerance);
}

View File

@@ -4,29 +4,30 @@
#include "frc/DriverStation.h" // NOLINT(build/include_order)
#include <units/math.h>
#include <units/time.h>
#include "TestBench.h"
#include "frc/RobotController.h"
#include "gtest/gtest.h"
#define EXPECT_NEAR_UNITS(val1, val2, eps) \
EXPECT_LE(units::math::abs(val1 - val2), eps)
using namespace frc;
constexpr double TIMER_TOLERANCE = 0.2;
constexpr int64_t TIMER_RUNTIME = 1000000; // 1 second
class DriverStationTest : public testing::Test {};
/**
* Test if the WaitForData function works
*/
TEST_F(DriverStationTest, WaitForData) {
uint64_t initialTime = RobotController::GetFPGATime();
TEST(DriverStationTest, WaitForData) {
units::microsecond_t initialTime(RobotController::GetFPGATime());
// 20ms waiting intervals * 50 = 1s
for (int i = 0; i < 50; i++) {
DriverStation::GetInstance().WaitForData();
}
uint64_t finalTime = RobotController::GetFPGATime();
units::microsecond_t finalTime(RobotController::GetFPGATime());
EXPECT_NEAR(TIMER_RUNTIME, finalTime - initialTime,
TIMER_TOLERANCE * TIMER_RUNTIME);
EXPECT_NEAR_UNITS(1_s, finalTime - initialTime, 200_ms);
}

View File

@@ -4,6 +4,8 @@
#include "frc/Encoder.h" // NOLINT(build/include_order)
#include <units/time.h>
#include "TestBench.h"
#include "frc/AnalogOutput.h"
#include "frc/AnalogTrigger.h"
@@ -13,7 +15,7 @@
using namespace frc;
static const double kDelayTime = 0.001;
static constexpr auto kDelayTime = 1_ms;
class FakeEncoderTest : public testing::Test {
protected:

View File

@@ -4,6 +4,8 @@
#include <algorithm>
#include <units/time.h>
#include "TestBench.h"
#include "frc/Encoder.h"
#include "frc/LinearFilter.h"
@@ -35,7 +37,7 @@ std::ostream& operator<<(std::ostream& os, MotorEncoderTestType const& type) {
return os;
}
static constexpr double kMotorTime = 0.5;
static constexpr auto kMotorTime = 0.5_s;
/**
* A fixture that includes a PWM motor controller and an encoder connected to
@@ -150,7 +152,7 @@ TEST_P(MotorEncoderTest, PositionPIDController) {
m_motorController->Set(std::clamp(speed, -0.2, 0.2));
}};
pidRunner.StartPeriodic(pidController.GetPeriod());
Wait(10.0);
Wait(10_s);
pidRunner.Stop();
RecordProperty("PIDError", pidController.GetPositionError());
@@ -177,7 +179,7 @@ TEST_P(MotorEncoderTest, VelocityPIDController) {
m_motorController->Set(std::clamp(speed, -0.3, 0.3));
}};
pidRunner.StartPeriodic(pidController.GetPeriod());
Wait(10.0);
Wait(10_s);
pidRunner.Stop();
RecordProperty("PIDError", pidController.GetPositionError());

View File

@@ -2,6 +2,8 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include <units/time.h>
#include "TestBench.h"
#include "frc/Encoder.h"
#include "frc/Timer.h"
@@ -13,8 +15,10 @@
using namespace frc;
enum MotorInvertingTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
static const double motorSpeed = 0.15;
static const double delayTime = 0.5;
static constexpr double kMotorSpeed = 0.15;
static constexpr auto kDelayTime = 0.5_s;
std::ostream& operator<<(std::ostream& os, MotorInvertingTestType const& type) {
switch (type) {
case TEST_VICTOR:
@@ -73,15 +77,15 @@ class MotorInvertingTest
TEST_P(MotorInvertingTest, InvertingPositive) {
Reset();
m_motorController->Set(motorSpeed);
m_motorController->Set(kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
bool initDirection = m_encoder->GetDirection();
m_motorController->SetInverted(true);
m_motorController->Set(motorSpeed);
m_motorController->Set(kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
EXPECT_TRUE(m_encoder->GetDirection() != initDirection)
<< "Inverting with Positive value does not change direction";
@@ -93,15 +97,15 @@ TEST_P(MotorInvertingTest, InvertingNegative) {
Reset();
m_motorController->SetInverted(false);
m_motorController->Set(-motorSpeed);
m_motorController->Set(-kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
bool initDirection = m_encoder->GetDirection();
m_motorController->SetInverted(true);
m_motorController->Set(-motorSpeed);
m_motorController->Set(-kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
EXPECT_TRUE(m_encoder->GetDirection() != initDirection)
<< "Inverting with Negative value does not change direction";
@@ -113,15 +117,15 @@ TEST_P(MotorInvertingTest, InvertingSwitchingPosToNeg) {
Reset();
m_motorController->SetInverted(false);
m_motorController->Set(motorSpeed);
m_motorController->Set(kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
bool initDirection = m_encoder->GetDirection();
m_motorController->SetInverted(true);
m_motorController->Set(-motorSpeed);
m_motorController->Set(-kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
EXPECT_TRUE(m_encoder->GetDirection() == initDirection)
<< "Inverting with Switching value does change direction";
@@ -133,15 +137,15 @@ TEST_P(MotorInvertingTest, InvertingSwitchingNegToPos) {
Reset();
m_motorController->SetInverted(false);
m_motorController->Set(-motorSpeed);
m_motorController->Set(-kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
bool initDirection = m_encoder->GetDirection();
m_motorController->SetInverted(true);
m_motorController->Set(motorSpeed);
m_motorController->Set(kMotorSpeed);
Wait(delayTime);
Wait(kDelayTime);
EXPECT_TRUE(m_encoder->GetDirection() == initDirection)
<< "Inverting with Switching value does change direction";

View File

@@ -27,10 +27,10 @@ TEST(NotifierTest, DISABLED_TestTimerNotifications) {
wpi::outs() << "notifier(notifierHandler, nullptr)...\n";
Notifier notifier(notifierHandler, nullptr);
wpi::outs() << "Start Periodic...\n";
notifier.StartPeriodic(1.0);
notifier.StartPeriodic(1_s);
wpi::outs() << "Wait...\n";
Wait(10.5);
Wait(10.5_s);
wpi::outs() << "...Wait\n";
EXPECT_EQ(10u, notifierCounter)

View File

@@ -16,10 +16,10 @@ using namespace frc;
/* The PCM switches the compressor up to a couple seconds after the pressure
switch changes. */
static const double kCompressorDelayTime = 3.0;
static constexpr auto kCompressorDelayTime = 3_s;
/* Solenoids should change much more quickly */
static const double kSolenoidDelayTime = 0.5;
static constexpr auto kSolenoidDelayTime = 0.5_s;
/* The voltage divider on the test bench should bring the compressor output
to around these values. */

View File

@@ -4,9 +4,8 @@
#include "frc/PowerDistributionPanel.h" // NOLINT(build/include_order)
#include <thread>
#include <hal/Ports.h>
#include <units/time.h>
#include "TestBench.h"
#include "frc/Timer.h"
@@ -17,7 +16,7 @@
using namespace frc;
static const double kMotorTime = 0.25;
static constexpr auto kMotorTime = 0.25_s;
class PowerDistributionPanelTest : public testing::Test {
protected:
@@ -50,7 +49,7 @@ TEST_F(PowerDistributionPanelTest, CheckRepeatedCalls) {
}
m_pdp->GetVoltage();
}
std::this_thread::sleep_for(std::chrono::milliseconds(20));
Wait(20_ms);
}
/**

View File

@@ -9,6 +9,7 @@
#include <networktables/NetworkTableInstance.h>
#include <ntcore.h>
#include <units/time.h>
#include "frc/Timer.h"
#include "gtest/gtest.h"
@@ -16,7 +17,7 @@
using namespace frc;
static const char* kFileName = "networktables.ini";
static const double kSaveTime = 1.2;
static constexpr auto kSaveTime = 1.2_s;
/**
* If we write a new networktables.ini with some sample values, test that
@@ -71,24 +72,24 @@ TEST(PreferencesTest, WritePreferencesToFile) {
Wait(kSaveTime);
preferences->PutString("testFilePutString", "Hello, preferences file");
preferences->PutInt("testFilePutInt", 1);
preferences->PutDouble("testFilePutDouble", 0.5);
preferences->PutFloat("testFilePutFloat", 0.25f);
preferences->PutBoolean("testFilePutBoolean", true);
preferences->PutLong("testFilePutLong", 1000000000000000000ll);
preferences->SetString("testFileSetString", "Hello, preferences file");
preferences->SetInt("testFileSetInt", 1);
preferences->SetDouble("testFileSetDouble", 0.5);
preferences->SetFloat("testFileSetFloat", 0.25f);
preferences->SetBoolean("testFileSetBoolean", true);
preferences->SetLong("testFileSetLong", 1000000000000000000ll);
Wait(kSaveTime);
static char const* kExpectedFileContents[] = {
"[NetworkTables Storage 3.0]",
"string \"/Preferences/.type\"=\"RobotPreferences\"",
"boolean \"/Preferences/testFilePutBoolean\"=true",
"double \"/Preferences/testFilePutDouble\"=0.5",
"double \"/Preferences/testFilePutFloat\"=0.25",
"double \"/Preferences/testFilePutInt\"=1",
"double \"/Preferences/testFilePutLong\"=1e+18",
"string \"/Preferences/testFilePutString\"=\"Hello, preferences file\""};
"boolean \"/Preferences/testFileSetBoolean\"=true",
"double \"/Preferences/testFileSetDouble\"=0.5",
"double \"/Preferences/testFileSetFloat\"=0.25",
"double \"/Preferences/testFileSetInt\"=1",
"double \"/Preferences/testFileSetLong\"=1e+18",
"string \"/Preferences/testFileSetString\"=\"Hello, preferences file\""};
std::ifstream preferencesFile(kFileName);
for (auto& kExpectedFileContent : kExpectedFileContents) {

View File

@@ -4,6 +4,8 @@
#include "frc/Relay.h" // NOLINT(build/include_order)
#include <units/time.h>
#include "TestBench.h"
#include "frc/DigitalInput.h"
#include "frc/Timer.h"
@@ -11,7 +13,7 @@
using namespace frc;
static const double kDelayTime = 0.01;
static constexpr auto kDelayTime = 10_ms;
class RelayTest : public testing::Test {
protected:

View File

@@ -53,7 +53,7 @@ class TestEnvironment : public testing::Environment {
std::terminate();
}
Wait(0.1);
Wait(0.1_s);
wpi::outs() << "Waiting for enable: " << enableCounter++ << "\n";
}

View File

@@ -4,6 +4,8 @@
#include <cmath>
#include <units/time.h>
#include "TestBench.h"
#include "frc/ADXL345_SPI.h"
#include "frc/AnalogGyro.h"
@@ -13,14 +15,14 @@
using namespace frc;
static constexpr double kServoResetTime = 2.0;
static constexpr auto kServoResetTime = 2_s;
static constexpr double kTestAngle = 90.0;
static constexpr double kTiltSetpoint0 = 0.22;
static constexpr double kTiltSetpoint45 = 0.45;
static constexpr double kTiltSetpoint90 = 0.68;
static constexpr double kTiltTime = 1.0;
static constexpr auto kTiltTime = 1_s;
static constexpr double kAccelerometerTolerance = 0.2;
static constexpr double kSensitivity = 0.013;
@@ -84,12 +86,12 @@ void TiltPanCameraTest::DefaultGyroAngle() {
void TiltPanCameraTest::GyroAngle() {
// Make sure that the gyro doesn't get jerked when the servo goes to zero.
m_pan->SetAngle(0.0);
Wait(0.5);
Wait(0.5_s);
m_gyro->Reset();
for (int32_t i = 0; i < 600; i++) {
m_pan->Set(i / 1000.0);
Wait(0.001);
Wait(1_ms);
}
double gyroAngle = m_gyro->GetAngle();
@@ -114,18 +116,18 @@ void TiltPanCameraTest::GyroCalibratedParameters() {
// Default gyro angle test
// Accumulator needs a small amount of time to reset before being tested
m_gyro->Reset();
Wait(0.001);
Wait(1_ms);
EXPECT_NEAR(0.0, m_gyro->GetAngle(), 1.0);
// Gyro angle test
// Make sure that the gyro doesn't get jerked when the servo goes to zero.
m_pan->SetAngle(0.0);
Wait(0.5);
Wait(0.5_s);
m_gyro->Reset();
for (int32_t i = 0; i < 600; i++) {
m_pan->Set(i / 1000.0);
Wait(0.001);
Wait(1_ms);
}
double gyroAngle = m_gyro->GetAngle();

View File

@@ -4,35 +4,19 @@
#include "frc/Timer.h" // NOLINT(build/include_order)
#include "TestBench.h"
#include <units/math.h>
#include "gtest/gtest.h"
using namespace frc;
#define EXPECT_NEAR_UNITS(val1, val2, eps) \
EXPECT_LE(units::math::abs(val1 - val2), eps)
static const double kWaitTime = 0.5;
TEST(TimerTest, Wait) {
auto initialTime = frc::Timer::GetFPGATimestamp();
class TimerTest : public testing::Test {
protected:
Timer* m_timer;
frc::Wait(500_ms);
void SetUp() override { m_timer = new Timer; }
auto finalTime = frc::Timer::GetFPGATimestamp();
void TearDown() override { delete m_timer; }
void Reset() { m_timer->Reset(); }
};
/**
* Test if the Wait function works
*/
TEST_F(TimerTest, Wait) {
Reset();
double initialTime = m_timer->GetFPGATimestamp();
Wait(kWaitTime);
double finalTime = m_timer->GetFPGATimestamp();
EXPECT_NEAR(kWaitTime, finalTime - initialTime, 0.001);
EXPECT_NEAR_UNITS(500_ms, finalTime - initialTime, 1_ms);
}

View File

@@ -149,8 +149,8 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) {
command3->Requires(&subsystem);
CommandGroup commandGroup;
commandGroup.AddSequential(command1, 1.0);
commandGroup.AddSequential(command2, 2.0);
commandGroup.AddSequential(command1, 1_s);
commandGroup.AddSequential(command2, 2_s);
commandGroup.AddSequential(command3);
AssertCommandState(command1, 0, 0, 0, 0, 0);
@@ -171,7 +171,7 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) {
AssertCommandState(command1, 1, 1, 1, 0, 0);
AssertCommandState(command2, 0, 0, 0, 0, 0);
AssertCommandState(command3, 0, 0, 0, 0, 0);
Wait(1); // command 1 timeout
Wait(1_s);
Scheduler::GetInstance()->Run();
AssertCommandState(command1, 1, 1, 1, 0, 1);
@@ -182,7 +182,7 @@ TEST_F(CommandTest, ThreeCommandOnSubSystem) {
AssertCommandState(command1, 1, 1, 1, 0, 1);
AssertCommandState(command2, 1, 2, 2, 0, 0);
AssertCommandState(command3, 0, 0, 0, 0, 0);
Wait(2); // command 2 timeout
Wait(2_s);
Scheduler::GetInstance()->Run();
AssertCommandState(command1, 1, 1, 1, 0, 1);
@@ -315,7 +315,7 @@ TEST_F(CommandTest,
class ModifiedMockCommand : public MockCommand {
public:
ModifiedMockCommand() : MockCommand() { SetTimeout(2.0); }
ModifiedMockCommand() : MockCommand() { SetTimeout(2_s); }
bool IsFinished() override {
return MockCommand::IsFinished() || IsTimedOut();
}
@@ -336,7 +336,7 @@ TEST_F(CommandTest, TwoSecondTimeout) {
AssertCommandState(&command, 1, 2, 2, 0, 0);
Scheduler::GetInstance()->Run();
AssertCommandState(&command, 1, 3, 3, 0, 0);
Wait(2);
Wait(2_s);
Scheduler::GetInstance()->Run();
AssertCommandState(&command, 1, 4, 4, 1, 0);
Scheduler::GetInstance()->Run();

View File

@@ -128,8 +128,8 @@ class DifferentialDrivePoseEstimator {
* calling UpdateWithTime(), then you must use a
* timestamp with an epoch since FPGA startup (i.e. the
* epoch of this timestamp is the same epoch as
* frc2::Timer::GetFPGATimestamp(). This means that
* you should use frc2::Timer::GetFPGATimestamp() as
* frc::Timer::GetFPGATimestamp(). This means that
* you should use frc::Timer::GetFPGATimestamp() as
* your time source in this case.
*/
void AddVisionMeasurement(const Pose2d& visionRobotPose,
@@ -155,9 +155,9 @@ class DifferentialDrivePoseEstimator {
* timestamp with an epoch since FPGA startup
* (i.e. the epoch of this timestamp is the
* same epoch as
* frc2::Timer::GetFPGATimestamp(). This means
* frc::Timer::GetFPGATimestamp(). This means
* that you should use
* frc2::Timer::GetFPGATimestamp() as your
* frc::Timer::GetFPGATimestamp() as your
* time source in this case.
* @param visionMeasurementStdDevs Standard deviations of the vision
* measurements. Increase these numbers to

View File

@@ -155,9 +155,9 @@ class MecanumDrivePoseEstimator {
* timestamp with an epoch since FPGA startup
* (i.e. the epoch of this timestamp is the
* same epoch as
* frc2::Timer::GetFPGATimestamp(). This means
* frc::Timer::GetFPGATimestamp(). This means
* that you should use
* frc2::Timer::GetFPGATimestamp() as your
* frc::Timer::GetFPGATimestamp() as your
* time source in this case.
* @param visionMeasurementStdDevs Standard deviations of the vision
* measurements. Increase these numbers to

View File

@@ -209,9 +209,9 @@ class SwerveDrivePoseEstimator {
* timestamp with an epoch since FPGA startup
* (i.e. the epoch of this timestamp is the
* same epoch as
* frc2::Timer::GetFPGATimestamp(). This means
* frc::Timer::GetFPGATimestamp(). This means
* that you should use
* frc2::Timer::GetFPGATimestamp() as your
* frc::Timer::GetFPGATimestamp() as your
* time source in this case.
* @param visionMeasurementStdDevs Standard deviations of the vision
* measurements. Increase these numbers to