mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[commands] Revert SubsystemBase deprecation/removal (#5634)
This commit is contained in:
@@ -14,7 +14,7 @@ import edu.wpi.first.math.controller.PIDController;
|
||||
*
|
||||
* <p>This class is provided by the NewCommands VendorDep
|
||||
*/
|
||||
public abstract class PIDSubsystem extends Subsystem {
|
||||
public abstract class PIDSubsystem extends SubsystemBase {
|
||||
protected final PIDController m_controller;
|
||||
protected boolean m_enabled;
|
||||
|
||||
|
||||
@@ -16,7 +16,7 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
*
|
||||
* <p>This class is provided by the NewCommands VendorDep
|
||||
*/
|
||||
public abstract class ProfiledPIDSubsystem extends Subsystem {
|
||||
public abstract class ProfiledPIDSubsystem extends SubsystemBase {
|
||||
protected final ProfiledPIDController m_controller;
|
||||
protected boolean m_enabled;
|
||||
|
||||
|
||||
@@ -4,10 +4,6 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based
|
||||
* framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc.) and
|
||||
@@ -17,34 +13,29 @@ import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
* their {@link Command#getRequirements()} method, and resources used within a subsystem should
|
||||
* generally remain encapsulated and not be shared by other parts of the robot.
|
||||
*
|
||||
* <p>Subsystems are automatically registered with the default scheduler in order for the {@link
|
||||
* Subsystem#periodic()} method to be called.
|
||||
* <p>Subsystems must be registered with the scheduler with the {@link
|
||||
* CommandScheduler#registerSubsystem(Subsystem...)} method in order for the {@link
|
||||
* Subsystem#periodic()} method to be called. It is recommended that this method be called from the
|
||||
* constructor of users' Subsystem implementations. The {@link SubsystemBase} class offers a simple
|
||||
* base for user implementations that handles this.
|
||||
*
|
||||
* <p>This class is provided by the NewCommands VendorDep
|
||||
*/
|
||||
public abstract class Subsystem implements Sendable {
|
||||
/** Constructor. */
|
||||
public Subsystem() {
|
||||
String name = this.getClass().getSimpleName();
|
||||
name = name.substring(name.lastIndexOf('.') + 1);
|
||||
SendableRegistry.addLW(this, name, name);
|
||||
CommandScheduler.getInstance().registerSubsystem(this);
|
||||
}
|
||||
|
||||
public interface Subsystem {
|
||||
/**
|
||||
* This method is called periodically by the {@link CommandScheduler}. Useful for updating
|
||||
* subsystem-specific state that you don't want to offload to a {@link Command}. Teams should try
|
||||
* to be consistent within their own codebases about which responsibilities will be handled by
|
||||
* Commands, and which will be handled here.
|
||||
*/
|
||||
public void periodic() {}
|
||||
default void periodic() {}
|
||||
|
||||
/**
|
||||
* This method is called periodically by the {@link CommandScheduler}. Useful for updating
|
||||
* subsystem-specific state that needs to be maintained for simulations, such as for updating
|
||||
* {@link edu.wpi.first.wpilibj.simulation} classes and setting simulated sensor readings.
|
||||
*/
|
||||
public void simulationPeriodic() {}
|
||||
default void simulationPeriodic() {}
|
||||
|
||||
/**
|
||||
* Sets the default {@link Command} of the subsystem. The default command will be automatically
|
||||
@@ -55,7 +46,7 @@ public abstract class Subsystem implements Sendable {
|
||||
*
|
||||
* @param defaultCommand the default command to associate with this subsystem
|
||||
*/
|
||||
public void setDefaultCommand(Command defaultCommand) {
|
||||
default void setDefaultCommand(Command defaultCommand) {
|
||||
CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand);
|
||||
}
|
||||
|
||||
@@ -63,7 +54,7 @@ public abstract class Subsystem implements Sendable {
|
||||
* Removes the default command for the subsystem. This will not cancel the default command if it
|
||||
* is currently running.
|
||||
*/
|
||||
public void removeDefaultCommand() {
|
||||
default void removeDefaultCommand() {
|
||||
CommandScheduler.getInstance().removeDefaultCommand(this);
|
||||
}
|
||||
|
||||
@@ -73,7 +64,7 @@ public abstract class Subsystem implements Sendable {
|
||||
*
|
||||
* @return the default command associated with this subsystem
|
||||
*/
|
||||
public Command getDefaultCommand() {
|
||||
default Command getDefaultCommand() {
|
||||
return CommandScheduler.getInstance().getDefaultCommand(this);
|
||||
}
|
||||
|
||||
@@ -83,51 +74,15 @@ public abstract class Subsystem implements Sendable {
|
||||
*
|
||||
* @return the scheduled command currently requiring this subsystem
|
||||
*/
|
||||
public Command getCurrentCommand() {
|
||||
default Command getCurrentCommand() {
|
||||
return CommandScheduler.getInstance().requiring(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the name of this Subsystem.
|
||||
*
|
||||
* @return Name
|
||||
*/
|
||||
public String getName() {
|
||||
return SendableRegistry.getName(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of this Subsystem.
|
||||
*
|
||||
* @param name name
|
||||
*/
|
||||
public void setName(String name) {
|
||||
SendableRegistry.setName(this, name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @return Subsystem name
|
||||
*/
|
||||
public String getSubsystem() {
|
||||
return SendableRegistry.getSubsystem(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @param subsystem subsystem name
|
||||
*/
|
||||
public void setSubsystem(String subsystem) {
|
||||
SendableRegistry.setSubsystem(this, subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Registers this subsystem with the {@link CommandScheduler}, allowing its {@link
|
||||
* Subsystem#periodic()} method to be called when the scheduler runs.
|
||||
*/
|
||||
public void register() {
|
||||
default void register() {
|
||||
CommandScheduler.getInstance().registerSubsystem(this);
|
||||
}
|
||||
|
||||
@@ -138,7 +93,7 @@ public abstract class Subsystem implements Sendable {
|
||||
* @return the command
|
||||
* @see InstantCommand
|
||||
*/
|
||||
public Command runOnce(Runnable action) {
|
||||
default Command runOnce(Runnable action) {
|
||||
return Commands.runOnce(action, this);
|
||||
}
|
||||
|
||||
@@ -150,7 +105,7 @@ public abstract class Subsystem implements Sendable {
|
||||
* @return the command
|
||||
* @see RunCommand
|
||||
*/
|
||||
public Command run(Runnable action) {
|
||||
default Command run(Runnable action) {
|
||||
return Commands.run(action, this);
|
||||
}
|
||||
|
||||
@@ -163,7 +118,7 @@ public abstract class Subsystem implements Sendable {
|
||||
* @return the command
|
||||
* @see StartEndCommand
|
||||
*/
|
||||
public Command startEnd(Runnable start, Runnable end) {
|
||||
default Command startEnd(Runnable start, Runnable end) {
|
||||
return Commands.startEnd(start, end, this);
|
||||
}
|
||||
|
||||
@@ -175,33 +130,7 @@ public abstract class Subsystem implements Sendable {
|
||||
* @param end the action to run on interrupt
|
||||
* @return the command
|
||||
*/
|
||||
public Command runEnd(Runnable run, Runnable end) {
|
||||
default Command runEnd(Runnable run, Runnable end) {
|
||||
return Commands.runEnd(run, end, this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Associates a {@link Sendable} with this Subsystem. Also update the child's name.
|
||||
*
|
||||
* @param name name to give child
|
||||
* @param child sendable
|
||||
*/
|
||||
public void addChild(String name, Sendable child) {
|
||||
SendableRegistry.addLW(child, getSubsystem(), name);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Subsystem");
|
||||
|
||||
builder.addBooleanProperty(".hasDefault", () -> getDefaultCommand() != null, null);
|
||||
builder.addStringProperty(
|
||||
".default",
|
||||
() -> getDefaultCommand() != null ? getDefaultCommand().getName() : "none",
|
||||
null);
|
||||
builder.addBooleanProperty(".hasCommand", () -> getCurrentCommand() != null, null);
|
||||
builder.addStringProperty(
|
||||
".command",
|
||||
() -> getCurrentCommand() != null ? getCurrentCommand().getName() : "none",
|
||||
null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,15 +4,84 @@
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import edu.wpi.first.util.sendable.Sendable;
|
||||
import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.util.sendable.SendableRegistry;
|
||||
|
||||
/**
|
||||
* A base for subsystems that handles registration in the constructor, and provides a more intuitive
|
||||
* method for setting the default command.
|
||||
*
|
||||
* <p>This class is provided by the NewCommands VendorDep
|
||||
*
|
||||
* @deprecated All functionality provided by {@link SubsystemBase} has been merged into {@link
|
||||
* Subsystem}. Use {@link Subsystem} instead.
|
||||
*/
|
||||
@Deprecated(since = "2024", forRemoval = true)
|
||||
@SuppressWarnings("PMD.AbstractClassWithoutAnyMethod")
|
||||
public abstract class SubsystemBase extends Subsystem {}
|
||||
public abstract class SubsystemBase implements Subsystem, Sendable {
|
||||
/** Constructor. */
|
||||
public SubsystemBase() {
|
||||
String name = this.getClass().getSimpleName();
|
||||
name = name.substring(name.lastIndexOf('.') + 1);
|
||||
SendableRegistry.addLW(this, name, name);
|
||||
CommandScheduler.getInstance().registerSubsystem(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the name of this Subsystem.
|
||||
*
|
||||
* @return Name
|
||||
*/
|
||||
public String getName() {
|
||||
return SendableRegistry.getName(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the name of this Subsystem.
|
||||
*
|
||||
* @param name name
|
||||
*/
|
||||
public void setName(String name) {
|
||||
SendableRegistry.setName(this, name);
|
||||
}
|
||||
|
||||
/**
|
||||
* Gets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @return Subsystem name
|
||||
*/
|
||||
public String getSubsystem() {
|
||||
return SendableRegistry.getSubsystem(this);
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @param subsystem subsystem name
|
||||
*/
|
||||
public void setSubsystem(String subsystem) {
|
||||
SendableRegistry.setSubsystem(this, subsystem);
|
||||
}
|
||||
|
||||
/**
|
||||
* Associates a {@link Sendable} with this Subsystem. Also update the child's name.
|
||||
*
|
||||
* @param name name to give child
|
||||
* @param child sendable
|
||||
*/
|
||||
public void addChild(String name, Sendable child) {
|
||||
SendableRegistry.addLW(child, getSubsystem(), name);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void initSendable(SendableBuilder builder) {
|
||||
builder.setSmartDashboardType("Subsystem");
|
||||
|
||||
builder.addBooleanProperty(".hasDefault", () -> getDefaultCommand() != null, null);
|
||||
builder.addStringProperty(
|
||||
".default",
|
||||
() -> getDefaultCommand() != null ? getDefaultCommand().getName() : "none",
|
||||
null);
|
||||
builder.addBooleanProperty(".hasCommand", () -> getCurrentCommand() != null, null);
|
||||
builder.addStringProperty(
|
||||
".command",
|
||||
() -> getCurrentCommand() != null ? getCurrentCommand().getName() : "none",
|
||||
null);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -14,7 +14,7 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
*
|
||||
* <p>This class is provided by the NewCommands VendorDep
|
||||
*/
|
||||
public abstract class TrapezoidProfileSubsystem extends Subsystem {
|
||||
public abstract class TrapezoidProfileSubsystem extends SubsystemBase {
|
||||
private final double m_period;
|
||||
private final TrapezoidProfile m_profile;
|
||||
|
||||
|
||||
@@ -8,12 +8,6 @@
|
||||
#include "frc2/command/Commands.h"
|
||||
|
||||
using namespace frc2;
|
||||
|
||||
Subsystem::Subsystem() {
|
||||
wpi::SendableRegistry::AddLW(this, GetTypeName(*this));
|
||||
CommandScheduler::GetInstance().RegisterSubsystem({this});
|
||||
}
|
||||
|
||||
Subsystem::~Subsystem() {
|
||||
CommandScheduler::GetInstance().UnregisterSubsystem(this);
|
||||
}
|
||||
@@ -39,26 +33,6 @@ Command* Subsystem::GetCurrentCommand() const {
|
||||
return CommandScheduler::GetInstance().Requiring(this);
|
||||
}
|
||||
|
||||
std::string Subsystem::GetName() const {
|
||||
return wpi::SendableRegistry::GetName(this);
|
||||
}
|
||||
|
||||
void Subsystem::SetName(std::string_view name) {
|
||||
wpi::SendableRegistry::SetName(this, name);
|
||||
}
|
||||
|
||||
std::string Subsystem::GetSubsystem() const {
|
||||
return wpi::SendableRegistry::GetSubsystem(this);
|
||||
}
|
||||
|
||||
void Subsystem::SetSubsystem(std::string_view name) {
|
||||
wpi::SendableRegistry::SetSubsystem(this, name);
|
||||
}
|
||||
|
||||
void Subsystem::AddChild(std::string name, wpi::Sendable* child) {
|
||||
wpi::SendableRegistry::AddLW(child, GetSubsystem(), name);
|
||||
}
|
||||
|
||||
void Subsystem::Register() {
|
||||
return CommandScheduler::GetInstance().RegisterSubsystem(this);
|
||||
}
|
||||
@@ -80,33 +54,3 @@ CommandPtr Subsystem::RunEnd(std::function<void()> run,
|
||||
std::function<void()> end) {
|
||||
return cmd::RunEnd(std::move(run), std::move(end), {this});
|
||||
}
|
||||
|
||||
void Subsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Subsystem");
|
||||
builder.AddBooleanProperty(
|
||||
".hasDefault", [this] { return GetDefaultCommand() != nullptr; },
|
||||
nullptr);
|
||||
builder.AddStringProperty(
|
||||
".default",
|
||||
[this]() -> std::string {
|
||||
auto command = GetDefaultCommand();
|
||||
if (command == nullptr) {
|
||||
return "none";
|
||||
}
|
||||
return command->GetName();
|
||||
},
|
||||
nullptr);
|
||||
builder.AddBooleanProperty(
|
||||
".hasCommand", [this] { return GetCurrentCommand() != nullptr; },
|
||||
nullptr);
|
||||
builder.AddStringProperty(
|
||||
".command",
|
||||
[this]() -> std::string {
|
||||
auto command = GetCurrentCommand();
|
||||
if (command == nullptr) {
|
||||
return "none";
|
||||
}
|
||||
return command->GetName();
|
||||
},
|
||||
nullptr);
|
||||
}
|
||||
|
||||
@@ -12,4 +12,57 @@
|
||||
|
||||
using namespace frc2;
|
||||
|
||||
SubsystemBase::SubsystemBase() {}
|
||||
SubsystemBase::SubsystemBase() {
|
||||
wpi::SendableRegistry::AddLW(this, GetTypeName(*this));
|
||||
CommandScheduler::GetInstance().RegisterSubsystem({this});
|
||||
}
|
||||
|
||||
void SubsystemBase::InitSendable(wpi::SendableBuilder& builder) {
|
||||
builder.SetSmartDashboardType("Subsystem");
|
||||
builder.AddBooleanProperty(
|
||||
".hasDefault", [this] { return GetDefaultCommand() != nullptr; },
|
||||
nullptr);
|
||||
builder.AddStringProperty(
|
||||
".default",
|
||||
[this]() -> std::string {
|
||||
auto command = GetDefaultCommand();
|
||||
if (command == nullptr) {
|
||||
return "none";
|
||||
}
|
||||
return command->GetName();
|
||||
},
|
||||
nullptr);
|
||||
builder.AddBooleanProperty(
|
||||
".hasCommand", [this] { return GetCurrentCommand() != nullptr; },
|
||||
nullptr);
|
||||
builder.AddStringProperty(
|
||||
".command",
|
||||
[this]() -> std::string {
|
||||
auto command = GetCurrentCommand();
|
||||
if (command == nullptr) {
|
||||
return "none";
|
||||
}
|
||||
return command->GetName();
|
||||
},
|
||||
nullptr);
|
||||
}
|
||||
|
||||
std::string SubsystemBase::GetName() const {
|
||||
return wpi::SendableRegistry::GetName(this);
|
||||
}
|
||||
|
||||
void SubsystemBase::SetName(std::string_view name) {
|
||||
wpi::SendableRegistry::SetName(this, name);
|
||||
}
|
||||
|
||||
std::string SubsystemBase::GetSubsystem() const {
|
||||
return wpi::SendableRegistry::GetSubsystem(this);
|
||||
}
|
||||
|
||||
void SubsystemBase::SetSubsystem(std::string_view name) {
|
||||
wpi::SendableRegistry::SetSubsystem(this, name);
|
||||
}
|
||||
|
||||
void SubsystemBase::AddChild(std::string name, wpi::Sendable* child) {
|
||||
wpi::SendableRegistry::AddLW(child, GetSubsystem(), name);
|
||||
}
|
||||
|
||||
@@ -6,7 +6,7 @@
|
||||
|
||||
#include <frc/controller/PIDController.h>
|
||||
|
||||
#include "frc2/command/Subsystem.h"
|
||||
#include "frc2/command/SubsystemBase.h"
|
||||
|
||||
namespace frc2 {
|
||||
/**
|
||||
@@ -17,7 +17,7 @@ namespace frc2 {
|
||||
*
|
||||
* @see PIDController
|
||||
*/
|
||||
class PIDSubsystem : public Subsystem {
|
||||
class PIDSubsystem : public SubsystemBase {
|
||||
public:
|
||||
/**
|
||||
* Creates a new PIDSubsystem.
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <frc/controller/ProfiledPIDController.h>
|
||||
#include <units/time.h>
|
||||
|
||||
#include "frc2/command/Subsystem.h"
|
||||
#include "frc2/command/SubsystemBase.h"
|
||||
|
||||
namespace frc2 {
|
||||
/**
|
||||
@@ -19,7 +19,7 @@ namespace frc2 {
|
||||
* @see ProfiledPIDController
|
||||
*/
|
||||
template <class Distance>
|
||||
class ProfiledPIDSubsystem : public Subsystem {
|
||||
class ProfiledPIDSubsystem : public SubsystemBase {
|
||||
using Distance_t = units::unit_t<Distance>;
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
|
||||
@@ -6,11 +6,8 @@
|
||||
|
||||
#include <concepts>
|
||||
#include <functional>
|
||||
#include <string>
|
||||
#include <utility>
|
||||
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
|
||||
#include "frc2/command/CommandScheduler.h"
|
||||
|
||||
namespace frc2 {
|
||||
@@ -27,19 +24,22 @@ class CommandPtr;
|
||||
* subsystem should generally remain encapsulated and not be shared by other
|
||||
* parts of the robot.
|
||||
*
|
||||
* <p>Subsystems are automatically registered with the scheduler with the
|
||||
* <p>Subsystems must be registered with the scheduler with the
|
||||
* CommandScheduler.RegisterSubsystem() method in order for the
|
||||
* Periodic() method to be called.
|
||||
* Periodic() method to be called. It is recommended that this method be called
|
||||
* from the constructor of users' Subsystem implementations. The
|
||||
* SubsystemBase class offers a simple base for user implementations
|
||||
* that handles this.
|
||||
*
|
||||
* This class is provided by the NewCommands VendorDep
|
||||
*
|
||||
* @see Command
|
||||
* @see CommandScheduler
|
||||
* @see SubsystemBase
|
||||
*/
|
||||
class Subsystem : public wpi::Sendable, public wpi::SendableHelper<Subsystem> {
|
||||
class Subsystem {
|
||||
public:
|
||||
~Subsystem() override;
|
||||
|
||||
virtual ~Subsystem();
|
||||
/**
|
||||
* This method is called periodically by the CommandScheduler. Useful for
|
||||
* updating subsystem-specific state that you don't want to offload to a
|
||||
@@ -111,43 +111,6 @@ class Subsystem : public wpi::Sendable, public wpi::SendableHelper<Subsystem> {
|
||||
*/
|
||||
void Register();
|
||||
|
||||
/**
|
||||
* Gets the name of this Subsystem.
|
||||
*
|
||||
* @return Name
|
||||
*/
|
||||
std::string GetName() const;
|
||||
|
||||
/**
|
||||
* Sets the name of this Subsystem.
|
||||
*
|
||||
* @param name name
|
||||
*/
|
||||
void SetName(std::string_view name);
|
||||
|
||||
/**
|
||||
* Gets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @return Subsystem name
|
||||
*/
|
||||
std::string GetSubsystem() const;
|
||||
|
||||
/**
|
||||
* Sets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @param name subsystem name
|
||||
*/
|
||||
void SetSubsystem(std::string_view name);
|
||||
|
||||
/**
|
||||
* Associate a Sendable with this Subsystem.
|
||||
* Also update the child's name.
|
||||
*
|
||||
* @param name name to give child
|
||||
* @param child sendable
|
||||
*/
|
||||
void AddChild(std::string name, wpi::Sendable* child);
|
||||
|
||||
/**
|
||||
* Constructs a command that runs an action once and finishes. Requires this
|
||||
* subsystem.
|
||||
@@ -185,10 +148,5 @@ class Subsystem : public wpi::Sendable, public wpi::SendableHelper<Subsystem> {
|
||||
*/
|
||||
[[nodiscard]]
|
||||
CommandPtr RunEnd(std::function<void()> run, std::function<void()> end);
|
||||
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
protected:
|
||||
Subsystem();
|
||||
};
|
||||
} // namespace frc2
|
||||
|
||||
@@ -4,7 +4,11 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <wpi/deprecated.h>
|
||||
#include <string>
|
||||
#include <string_view>
|
||||
|
||||
#include <wpi/sendable/Sendable.h>
|
||||
#include <wpi/sendable/SendableHelper.h>
|
||||
|
||||
#include "frc2/command/Subsystem.h"
|
||||
|
||||
@@ -14,13 +18,51 @@ namespace frc2 {
|
||||
* provides a more intuitive method for setting the default command.
|
||||
*
|
||||
* This class is provided by the NewCommands VendorDep
|
||||
*
|
||||
* @deprecated All functionality provided by SubsystemBase has been merged into
|
||||
* Subsystem. Use Subsystem instead.
|
||||
*/
|
||||
class [[deprecated("Use Subsystem instead")]] SubsystemBase : public Subsystem {
|
||||
class SubsystemBase : public Subsystem,
|
||||
public wpi::Sendable,
|
||||
public wpi::SendableHelper<SubsystemBase> {
|
||||
public:
|
||||
void InitSendable(wpi::SendableBuilder& builder) override;
|
||||
|
||||
/**
|
||||
* Gets the name of this Subsystem.
|
||||
*
|
||||
* @return Name
|
||||
*/
|
||||
std::string GetName() const;
|
||||
|
||||
/**
|
||||
* Sets the name of this Subsystem.
|
||||
*
|
||||
* @param name name
|
||||
*/
|
||||
void SetName(std::string_view name);
|
||||
|
||||
/**
|
||||
* Gets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @return Subsystem name
|
||||
*/
|
||||
std::string GetSubsystem() const;
|
||||
|
||||
/**
|
||||
* Sets the subsystem name of this Subsystem.
|
||||
*
|
||||
* @param name subsystem name
|
||||
*/
|
||||
void SetSubsystem(std::string_view name);
|
||||
|
||||
/**
|
||||
* Associate a Sendable with this Subsystem.
|
||||
* Also update the child's name.
|
||||
*
|
||||
* @param name name to give child
|
||||
* @param child sendable
|
||||
*/
|
||||
void AddChild(std::string name, wpi::Sendable* child);
|
||||
|
||||
protected:
|
||||
WPI_DEPRECATED("Use Subsystem instead")
|
||||
SubsystemBase();
|
||||
};
|
||||
} // namespace frc2
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
#include <units/time.h>
|
||||
|
||||
#include "frc2/command/Subsystem.h"
|
||||
#include "frc2/command/SubsystemBase.h"
|
||||
|
||||
namespace frc2 {
|
||||
/**
|
||||
@@ -18,7 +18,7 @@ namespace frc2 {
|
||||
* This class is provided by the NewCommands VendorDep
|
||||
*/
|
||||
template <class Distance>
|
||||
class TrapezoidProfileSubsystem : public Subsystem {
|
||||
class TrapezoidProfileSubsystem : public SubsystemBase {
|
||||
using Distance_t = units::unit_t<Distance>;
|
||||
using Velocity =
|
||||
units::compound_unit<Distance, units::inverse<units::seconds>>;
|
||||
|
||||
@@ -15,7 +15,7 @@ class CommandRequirementsTest extends CommandTestBase {
|
||||
@Test
|
||||
void requirementInterruptTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement);
|
||||
Command interrupted = interruptedHolder.getMock();
|
||||
@@ -42,7 +42,7 @@ class CommandRequirementsTest extends CommandTestBase {
|
||||
@Test
|
||||
void requirementUninterruptibleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
|
||||
Command notInterrupted =
|
||||
new RunCommand(() -> {}, requirement)
|
||||
@@ -61,7 +61,7 @@ class CommandRequirementsTest extends CommandTestBase {
|
||||
@Test
|
||||
void defaultCommandRequirementErrorTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem system = new Subsystem() {};
|
||||
Subsystem system = new SubsystemBase() {};
|
||||
|
||||
Command missingRequirement = new WaitUntilCommand(() -> false);
|
||||
|
||||
|
||||
@@ -46,9 +46,9 @@ class ConditionalCommandTest extends CommandTestBase {
|
||||
|
||||
@Test
|
||||
void conditionalCommandRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
|
||||
@@ -14,7 +14,7 @@ class DefaultCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void defaultCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new Subsystem() {};
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand);
|
||||
Command defaultCommand = defaultHolder.getMock();
|
||||
@@ -29,7 +29,7 @@ class DefaultCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void defaultCommandInterruptResumeTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new Subsystem() {};
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand);
|
||||
Command defaultCommand = defaultHolder.getMock();
|
||||
@@ -54,7 +54,7 @@ class DefaultCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void defaultCommandDisableResumeTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new Subsystem() {};
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand);
|
||||
Command defaultCommand = defaultHolder.getMock();
|
||||
|
||||
@@ -90,10 +90,10 @@ class ParallelCommandGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelGroupRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system4 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
Subsystem system4 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
@@ -115,9 +115,9 @@ class ParallelCommandGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelGroupRequirementErrorTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
|
||||
@@ -87,10 +87,10 @@ class ParallelDeadlineGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelDeadlineRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system4 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
Subsystem system4 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
@@ -112,9 +112,9 @@ class ParallelDeadlineGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelDeadlineRequirementErrorTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
|
||||
@@ -92,10 +92,10 @@ class ParallelRaceGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelRaceRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system4 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
Subsystem system4 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
@@ -117,9 +117,9 @@ class ParallelRaceGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelRaceRequirementErrorTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
@@ -131,8 +131,8 @@ class ParallelRaceGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void parallelRaceOnlyCallsEndOnceTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1);
|
||||
Command command1 = command1Holder.getMock();
|
||||
|
||||
@@ -48,7 +48,7 @@ class SchedulerTest extends CommandTestBase {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
Subsystem system =
|
||||
new Subsystem() {
|
||||
new SubsystemBase() {
|
||||
@Override
|
||||
public void periodic() {
|
||||
counter.incrementAndGet();
|
||||
@@ -67,7 +67,7 @@ class SchedulerTest extends CommandTestBase {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
Subsystem system =
|
||||
new Subsystem() {
|
||||
new SubsystemBase() {
|
||||
@Override
|
||||
public void periodic() {
|
||||
counter.incrementAndGet();
|
||||
|
||||
@@ -25,7 +25,7 @@ class SchedulingRecursionTest extends CommandTestBase {
|
||||
void cancelFromInitialize(InterruptionBehavior interruptionBehavior) {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean hasOtherRun = new AtomicBoolean();
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
Command selfCancels =
|
||||
new Command() {
|
||||
{
|
||||
@@ -62,7 +62,7 @@ class SchedulingRecursionTest extends CommandTestBase {
|
||||
void defaultCommandGetsRescheduledAfterSelfCanceling(InterruptionBehavior interruptionBehavior) {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean hasOtherRun = new AtomicBoolean();
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
Command selfCancels =
|
||||
new Command() {
|
||||
{
|
||||
@@ -119,7 +119,7 @@ class SchedulingRecursionTest extends CommandTestBase {
|
||||
void scheduleFromEndCancel() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
InstantCommand other = new InstantCommand(() -> {}, requirement);
|
||||
Command selfCancels =
|
||||
new Command() {
|
||||
@@ -146,7 +146,7 @@ class SchedulingRecursionTest extends CommandTestBase {
|
||||
void scheduleFromEndInterrupt() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
InstantCommand other = new InstantCommand(() -> {}, requirement);
|
||||
Command selfCancels =
|
||||
new Command() {
|
||||
@@ -175,7 +175,7 @@ class SchedulingRecursionTest extends CommandTestBase {
|
||||
void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehavior) {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
Subsystem requirement = new Subsystem() {};
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
Command other =
|
||||
new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior);
|
||||
Command defaultCommand =
|
||||
|
||||
@@ -75,10 +75,10 @@ class SelectCommandTest extends CommandTestBase implements MultiCompositionTestB
|
||||
|
||||
@Test
|
||||
void selectCommandRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system4 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
Subsystem system4 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
|
||||
@@ -100,10 +100,10 @@ class SequentialCommandGroupTest extends CommandTestBase
|
||||
|
||||
@Test
|
||||
void sequentialGroupRequirementTest() {
|
||||
Subsystem system1 = new Subsystem() {};
|
||||
Subsystem system2 = new Subsystem() {};
|
||||
Subsystem system3 = new Subsystem() {};
|
||||
Subsystem system4 = new Subsystem() {};
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
Subsystem system4 = new SubsystemBase() {};
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
|
||||
@@ -13,13 +13,13 @@
|
||||
|
||||
#include "frc2/command/CommandHelper.h"
|
||||
#include "frc2/command/CommandScheduler.h"
|
||||
#include "frc2/command/Subsystem.h"
|
||||
#include "frc2/command/SubsystemBase.h"
|
||||
#include "gmock/gmock.h"
|
||||
#include "make_vector.h"
|
||||
|
||||
namespace frc2 {
|
||||
|
||||
class TestSubsystem : public Subsystem {
|
||||
class TestSubsystem : public SubsystemBase {
|
||||
public:
|
||||
explicit TestSubsystem(std::function<void()> periodic = [] {})
|
||||
: m_periodic{periodic} {}
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
class ReplaceMeSubsystem2 : public frc2::Subsystem {
|
||||
class ReplaceMeSubsystem2 : public frc2::SubsystemBase {
|
||||
public:
|
||||
ReplaceMeSubsystem2();
|
||||
|
||||
|
||||
@@ -8,11 +8,11 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -11,11 +11,11 @@
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Commands.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -8,13 +8,13 @@
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/trajectory/TrapezoidProfile.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/length.h>
|
||||
|
||||
#include "Constants.h"
|
||||
#include "ExampleSmartMotorController.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -8,11 +8,11 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -6,14 +6,14 @@
|
||||
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
/**
|
||||
* The claw subsystem is a simple system with a motor for opening and closing.
|
||||
* If using stronger motors, you should probably use a sensor so that the
|
||||
* motors don't stall.
|
||||
*/
|
||||
class Claw : public frc2::Subsystem {
|
||||
class Claw : public frc2::SubsystemBase {
|
||||
public:
|
||||
Claw();
|
||||
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
namespace frc {
|
||||
class Joystick;
|
||||
@@ -21,7 +21,7 @@ class Joystick;
|
||||
* the robots chassis. These include four drive motors, a left and right encoder
|
||||
* and a gyro.
|
||||
*/
|
||||
class Drivetrain : public frc2::Subsystem {
|
||||
class Drivetrain : public frc2::SubsystemBase {
|
||||
public:
|
||||
Drivetrain();
|
||||
|
||||
|
||||
@@ -9,12 +9,12 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/angle.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
}
|
||||
|
||||
void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
Subsystem::InitSendable(builder);
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.AddDoubleProperty(
|
||||
|
||||
@@ -25,7 +25,7 @@ frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
|
||||
}
|
||||
|
||||
void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
Subsystem::InitSendable(builder);
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.AddBooleanProperty(
|
||||
|
||||
@@ -8,11 +8,11 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -7,11 +7,11 @@
|
||||
#include <frc/DoubleSolenoid.h>
|
||||
#include <frc/PneumaticsControlModule.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class HatchSubsystem : public frc2::Subsystem {
|
||||
class HatchSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
HatchSubsystem();
|
||||
|
||||
|
||||
@@ -47,7 +47,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
|
||||
}
|
||||
|
||||
void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
Subsystem::InitSendable(builder);
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish encoder distances to telemetry.
|
||||
builder.AddDoubleProperty(
|
||||
|
||||
@@ -21,7 +21,7 @@ void HatchSubsystem::ReleaseHatch() {
|
||||
}
|
||||
|
||||
void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
|
||||
Subsystem::InitSendable(builder);
|
||||
SubsystemBase::InitSendable(builder);
|
||||
|
||||
// Publish the solenoid state to telemetry.
|
||||
builder.AddBooleanProperty(
|
||||
|
||||
@@ -8,11 +8,11 @@
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -6,11 +6,11 @@
|
||||
|
||||
#include <frc/DoubleSolenoid.h>
|
||||
#include <frc/PneumaticsControlModule.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class HatchSubsystem : public frc2::Subsystem {
|
||||
class HatchSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
HatchSubsystem();
|
||||
|
||||
|
||||
@@ -13,11 +13,11 @@
|
||||
#include <frc/kinematics/MecanumDriveOdometry.h>
|
||||
#include <frc/kinematics/MecanumDriveWheelSpeeds.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -11,12 +11,12 @@
|
||||
#include <frc/kinematics/DifferentialDriveOdometry.h>
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/voltage.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -11,12 +11,12 @@
|
||||
#include <frc/motorcontrol/MotorControllerGroup.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/length.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class Drive : public frc2::Subsystem {
|
||||
class Drive : public frc2::SubsystemBase {
|
||||
public:
|
||||
Drive();
|
||||
/**
|
||||
|
||||
@@ -9,11 +9,11 @@
|
||||
#include <frc/DoubleSolenoid.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class Intake : public frc2::Subsystem {
|
||||
class Intake : public frc2::SubsystemBase {
|
||||
public:
|
||||
Intake() = default;
|
||||
|
||||
|
||||
@@ -8,12 +8,12 @@
|
||||
#include <frc/Compressor.h>
|
||||
#include <frc/PneumaticsControlModule.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/pressure.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class Pneumatics : frc2::Subsystem {
|
||||
class Pneumatics : frc2::SubsystemBase {
|
||||
public:
|
||||
Pneumatics();
|
||||
/** Returns a command that disables the compressor indefinitely. */
|
||||
|
||||
@@ -11,13 +11,13 @@
|
||||
#include <frc/controller/SimpleMotorFeedforward.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/angle.h>
|
||||
#include <units/angular_velocity.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class Shooter : public frc2::Subsystem {
|
||||
class Shooter : public frc2::SubsystemBase {
|
||||
public:
|
||||
Shooter();
|
||||
|
||||
|
||||
@@ -7,11 +7,11 @@
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class Storage : frc2::Subsystem {
|
||||
class Storage : frc2::SubsystemBase {
|
||||
public:
|
||||
Storage();
|
||||
/** Returns a command that runs the storage motor indefinitely. */
|
||||
|
||||
@@ -8,12 +8,12 @@
|
||||
#include <frc/Encoder.h>
|
||||
#include <frc/drive/DifferentialDrive.h>
|
||||
#include <frc/motorcontrol/Spark.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/length.h>
|
||||
|
||||
#include "sensors/RomiGyro.h"
|
||||
|
||||
class Drivetrain : public frc2::Subsystem {
|
||||
class Drivetrain : public frc2::SubsystemBase {
|
||||
public:
|
||||
static constexpr double kCountsPerRevolution = 1440.0;
|
||||
static constexpr units::meter_t kWheelDiameter = 70_mm;
|
||||
|
||||
@@ -8,7 +8,7 @@
|
||||
|
||||
#include <frc/DigitalInput.h>
|
||||
#include <frc/DigitalOutput.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the Romi
|
||||
@@ -20,7 +20,7 @@
|
||||
* DIO 2 - Button C (input) or Red LED (output)
|
||||
* DIO 3 - Yellow LED (output only)
|
||||
*/
|
||||
class OnBoardIO : public frc2::Subsystem {
|
||||
class OnBoardIO : public frc2::SubsystemBase {
|
||||
public:
|
||||
enum ChannelMode { INPUT, OUTPUT };
|
||||
OnBoardIO(OnBoardIO::ChannelMode dio1, OnBoardIO::ChannelMode dio2);
|
||||
|
||||
@@ -15,12 +15,12 @@
|
||||
#include <frc/simulation/DifferentialDrivetrainSim.h>
|
||||
#include <frc/simulation/EncoderSim.h>
|
||||
#include <frc/smartdashboard/Field2d.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
#include <units/voltage.h>
|
||||
|
||||
#include "Constants.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -14,12 +14,12 @@
|
||||
#include <frc/kinematics/SwerveDriveKinematics.h>
|
||||
#include <frc/kinematics/SwerveDriveOdometry.h>
|
||||
#include <frc/motorcontrol/PWMSparkMax.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
#include "Constants.h"
|
||||
#include "SwerveModule.h"
|
||||
|
||||
class DriveSubsystem : public frc2::Subsystem {
|
||||
class DriveSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
DriveSubsystem();
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
#pragma once
|
||||
|
||||
#include <frc2/command/CommandPtr.h>
|
||||
#include <frc2/command/Subsystem.h>
|
||||
#include <frc2/command/SubsystemBase.h>
|
||||
|
||||
class ExampleSubsystem : public frc2::Subsystem {
|
||||
class ExampleSubsystem : public frc2::SubsystemBase {
|
||||
public:
|
||||
ExampleSubsystem();
|
||||
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.subsystem2;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class ReplaceMeSubsystem extends Subsystem {
|
||||
public class ReplaceMeSubsystem extends SubsystemBase {
|
||||
/** Creates a new ReplaceMeSubsystem. */
|
||||
public ReplaceMeSubsystem() {}
|
||||
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final ExampleSmartMotorController m_leftLeader =
|
||||
new ExampleSmartMotorController(DriveConstants.kLeftMotor1Port);
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -8,13 +8,13 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Constants.ClawConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Victor;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* The claw subsystem is a simple system with a motor for opening and closing. If using stronger
|
||||
* motors, you should probably use a sensor so that the motors don't stall.
|
||||
*/
|
||||
public class Claw extends Subsystem {
|
||||
public class Claw extends SubsystemBase {
|
||||
private final Victor m_motor = new Victor(ClawConstants.kMotorPort);
|
||||
private final DigitalInput m_contact = new DigitalInput(ClawConstants.kContactPort);
|
||||
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
/**
|
||||
* The Drivetrain subsystem incorporates the sensors and actuators attached to the robots chassis.
|
||||
* These include four drive motors, a left and right encoder and a gyro.
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -12,10 +12,10 @@ import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
private final PWMSparkMax m_frontLeft = new PWMSparkMax(DriveConstants.kFrontLeftMotorPort);
|
||||
private final PWMSparkMax m_rearLeft = new PWMSparkMax(DriveConstants.kRearLeftMotorPort);
|
||||
private final PWMSparkMax m_frontRight = new PWMSparkMax(DriveConstants.kFrontRightMotorPort);
|
||||
|
||||
@@ -13,9 +13,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,10 +10,10 @@ import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.DriveConsta
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class Drive extends Subsystem {
|
||||
public class Drive extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Intake extends Subsystem {
|
||||
public class Intake extends SubsystemBase {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
|
||||
|
||||
// Double solenoid connected to two channels of a PCM with the default CAN ID
|
||||
|
||||
@@ -9,10 +9,10 @@ import edu.wpi.first.wpilibj.Compressor;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/** Subsystem for managing the compressor, pressure sensor, etc. */
|
||||
public class Pneumatics extends Subsystem {
|
||||
public class Pneumatics extends SubsystemBase {
|
||||
// External analog pressure sensor
|
||||
// product-specific voltage->pressure conversion, see product manual
|
||||
// in this case, 250(V/5)-25
|
||||
|
||||
@@ -13,9 +13,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Shooter extends Subsystem {
|
||||
public class Shooter extends SubsystemBase {
|
||||
private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort);
|
||||
private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort);
|
||||
private final Encoder m_shooterEncoder =
|
||||
|
||||
@@ -9,9 +9,9 @@ import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.Stor
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Storage extends Subsystem {
|
||||
public class Storage extends SubsystemBase {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort);
|
||||
private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort);
|
||||
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.romireference.sensors.RomiGyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the Romi reference robot. This includes the pushbuttons
|
||||
@@ -17,7 +17,7 @@ import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
* <p>DIO 0 - Button A (input only) DIO 1 - Button B (input) or Green LED (output) DIO 2 - Button C
|
||||
* (input) or Red LED (output) DIO 3 - Yellow LED (output only)
|
||||
*/
|
||||
public class OnBoardIO extends Subsystem {
|
||||
public class OnBoardIO extends SubsystemBase {
|
||||
private final DigitalInput m_buttonA = new DigitalInput(0);
|
||||
private final DigitalOutput m_yellowLed = new DigitalOutput(3);
|
||||
|
||||
|
||||
@@ -22,9 +22,9 @@ import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -12,9 +12,9 @@ import edu.wpi.first.math.kinematics.SwerveModulePosition;
|
||||
import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// Robot swerve modules
|
||||
private final SwerveModule m_frontLeft =
|
||||
new SwerveModule(
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.xrpreference.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.devices.XRPServo;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Arm extends Subsystem {
|
||||
public class Arm extends SubsystemBase {
|
||||
private final XRPServo m_armServo;
|
||||
|
||||
/** Creates a new Arm. */
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.devices.XRPMotor;
|
||||
import edu.wpi.first.wpilibj.examples.xrpreference.sensors.XRPGyro;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class Drivetrain extends Subsystem {
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
private static final double kGearRatio =
|
||||
(30.0 / 14.0) * (28.0 / 16.0) * (36.0 / 9.0) * (26.0 / 8.0); // 48.75:1
|
||||
private static final double kCountsPerMotorShaftRev = 12.0;
|
||||
|
||||
@@ -6,13 +6,13 @@ package edu.wpi.first.wpilibj.examples.xrpreference.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the XRP Reference Robot. This includes the USER
|
||||
* pushbutton and LED
|
||||
*/
|
||||
public class XRPOnBoardIO extends Subsystem {
|
||||
public class XRPOnBoardIO extends SubsystemBase {
|
||||
private final DigitalInput m_button = new DigitalInput(0);
|
||||
private final DigitalOutput m_led = new DigitalOutput(1);
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.templates.commandbased.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class ExampleSubsystem extends Subsystem {
|
||||
public class ExampleSubsystem extends SubsystemBase {
|
||||
/** Creates a new ExampleSubsystem. */
|
||||
public ExampleSubsystem() {}
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.templates.romicommandbased.subsystems;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class RomiDrivetrain extends Subsystem {
|
||||
public class RomiDrivetrain extends SubsystemBase {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.templates.xrpcommandbased.subsystems;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.templates.xrpcommandbased.devices.XRPMotor;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class XRPDrivetrain extends Subsystem {
|
||||
public class XRPDrivetrain extends SubsystemBase {
|
||||
private static final double kGearRatio =
|
||||
(30.0 / 14.0) * (28.0 / 16.0) * (36.0 / 9.0) * (26.0 / 8.0); // 48.75:1
|
||||
private static final double kCountsPerMotorShaftRev = 12.0;
|
||||
|
||||
Reference in New Issue
Block a user