mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[build] Apply spotless for java formatting (#1768)
Update checkstyle config to be compatible with spotless. Co-authored-by: Austin Shalit <austinshalit@gmail.com>
This commit is contained in:
@@ -14,13 +14,11 @@ public class ReplaceMeCommand extends Command {
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
protected void initialize() {}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
@Override
|
||||
protected void execute() {
|
||||
}
|
||||
protected void execute() {}
|
||||
|
||||
// Make this return true when this Command no longer needs to run execute()
|
||||
@Override
|
||||
@@ -30,12 +28,10 @@ public class ReplaceMeCommand extends Command {
|
||||
|
||||
// Called once after isFinished returns true
|
||||
@Override
|
||||
protected void end() {
|
||||
}
|
||||
protected void end() {}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
@Override
|
||||
protected void interrupted() {
|
||||
}
|
||||
protected void interrupted() {}
|
||||
}
|
||||
|
||||
@@ -7,27 +7,22 @@ package edu.wpi.first.wpilibj.commands.command2;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
public class ReplaceMeCommand extends CommandBase {
|
||||
/**
|
||||
* Creates a new ReplaceMeCommand.
|
||||
*/
|
||||
/** Creates a new ReplaceMeCommand. */
|
||||
public ReplaceMeCommand() {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
}
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
}
|
||||
public void initialize() {}
|
||||
|
||||
// Called every time the scheduler runs while the command is scheduled.
|
||||
@Override
|
||||
public void execute() {
|
||||
}
|
||||
public void execute() {}
|
||||
|
||||
// Called once the command ends or is interrupted.
|
||||
@Override
|
||||
public void end(boolean interrupted) {
|
||||
}
|
||||
public void end(boolean interrupted) {}
|
||||
|
||||
// Returns true when the command should end.
|
||||
@Override
|
||||
|
||||
@@ -7,9 +7,7 @@ package edu.wpi.first.wpilibj.commands.commandgroup;
|
||||
import edu.wpi.first.wpilibj.command.CommandGroup;
|
||||
|
||||
public class ReplaceMeCommandGroup extends CommandGroup {
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public ReplaceMeCommandGroup() {
|
||||
// Add Commands here:
|
||||
// e.g. addSequential(new Command1());
|
||||
|
||||
@@ -4,8 +4,5 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.emptyclass;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
public class ReplaceMeEmptyClass {
|
||||
}
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMeEmptyClass {}
|
||||
|
||||
@@ -6,13 +6,9 @@ package edu.wpi.first.wpilibj.commands.instant;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.InstantCommand;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMeInstantCommand extends InstantCommand {
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public ReplaceMeInstantCommand() {
|
||||
super();
|
||||
// Use requires() here to declare subsystem dependencies
|
||||
@@ -21,7 +17,5 @@ public class ReplaceMeInstantCommand extends InstantCommand {
|
||||
|
||||
// Called once when the command executes
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
|
||||
protected void initialize() {}
|
||||
}
|
||||
|
||||
@@ -16,6 +16,5 @@ public class ReplaceMeInstantCommand extends InstantCommand {
|
||||
|
||||
// Called when the command is initially scheduled.
|
||||
@Override
|
||||
public void initialize() {
|
||||
}
|
||||
public void initialize() {}
|
||||
}
|
||||
|
||||
@@ -10,9 +10,7 @@ import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeParallelCommandGroup extends ParallelCommandGroup {
|
||||
/**
|
||||
* Creates a new ReplaceMeParallelCommandGroup.
|
||||
*/
|
||||
/** Creates a new ReplaceMeParallelCommandGroup. */
|
||||
public ReplaceMeParallelCommandGroup() {
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
|
||||
@@ -11,9 +11,7 @@ import edu.wpi.first.wpilibj2.command.ParallelDeadlineGroup;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeParallelDeadlineGroup extends ParallelDeadlineGroup {
|
||||
/**
|
||||
* Creates a new ReplaceMeParallelDeadlineGroup.
|
||||
*/
|
||||
/** Creates a new ReplaceMeParallelDeadlineGroup. */
|
||||
public ReplaceMeParallelDeadlineGroup() {
|
||||
// Add the deadline command in the super() call. Add other commands using
|
||||
// addCommands().
|
||||
|
||||
@@ -10,9 +10,7 @@ import edu.wpi.first.wpilibj2.command.ParallelRaceGroup;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeParallelRaceGroup extends ParallelRaceGroup {
|
||||
/**
|
||||
* Creates a new ReplaceMeParallelRaceGroup.
|
||||
*/
|
||||
/** Creates a new ReplaceMeParallelRaceGroup. */
|
||||
public ReplaceMeParallelRaceGroup() {
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
|
||||
@@ -11,9 +11,7 @@ import edu.wpi.first.wpilibj2.command.PIDCommand;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMePIDCommand extends PIDCommand {
|
||||
/**
|
||||
* Creates a new ReplaceMePIDCommand.
|
||||
*/
|
||||
/** Creates a new ReplaceMePIDCommand. */
|
||||
public ReplaceMePIDCommand() {
|
||||
super(
|
||||
// The controller that the command will use
|
||||
|
||||
@@ -6,13 +6,9 @@ package edu.wpi.first.wpilibj.commands.pidsubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.PIDSubsystem;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMePIDSubsystem extends PIDSubsystem {
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public ReplaceMePIDSubsystem() {
|
||||
// Intert a subsystem name and PID values here
|
||||
super("SubsystemName", 1, 2, 3);
|
||||
|
||||
@@ -8,9 +8,7 @@ import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
public class ReplaceMePIDSubsystem extends PIDSubsystem {
|
||||
/**
|
||||
* Creates a new ReplaceMePIDSubsystem.
|
||||
*/
|
||||
/** Creates a new ReplaceMePIDSubsystem. */
|
||||
public ReplaceMePIDSubsystem() {
|
||||
super(
|
||||
// The PIDController used by the subsystem
|
||||
|
||||
@@ -12,15 +12,15 @@ import edu.wpi.first.wpilibj2.command.ProfiledPIDCommand;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeProfiledPIDCommand extends ProfiledPIDCommand {
|
||||
/**
|
||||
* Creates a new ReplaceMeProfiledPIDCommand.
|
||||
*/
|
||||
/** Creates a new ReplaceMeProfiledPIDCommand. */
|
||||
public ReplaceMeProfiledPIDCommand() {
|
||||
super(
|
||||
// The ProfiledPIDController used by the command
|
||||
new ProfiledPIDController(
|
||||
// The PID gains
|
||||
0, 0, 0,
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
// The motion profile constraints
|
||||
new TrapezoidProfile.Constraints(0, 0)),
|
||||
// This should return the measurement
|
||||
|
||||
@@ -9,15 +9,16 @@ import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;
|
||||
|
||||
public class ReplaceMeProfiledPIDSubsystem extends ProfiledPIDSubsystem {
|
||||
/**
|
||||
* Creates a new ReplaceMeProfiledPIDSubsystem.
|
||||
*/
|
||||
/** Creates a new ReplaceMeProfiledPIDSubsystem. */
|
||||
public ReplaceMeProfiledPIDSubsystem() {
|
||||
super(
|
||||
// The ProfiledPIDController used by the subsystem
|
||||
new ProfiledPIDController(0, 0, 0,
|
||||
// The motion profile constraints
|
||||
new TrapezoidProfile.Constraints(0, 0)));
|
||||
new ProfiledPIDController(
|
||||
0,
|
||||
0,
|
||||
0,
|
||||
// The motion profile constraints
|
||||
new TrapezoidProfile.Constraints(0, 0)));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -10,9 +10,7 @@ import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeSequentialCommandGroup extends SequentialCommandGroup {
|
||||
/**
|
||||
* Creates a new ReplaceMeSequentialCommandGroup.
|
||||
*/
|
||||
/** Creates a new ReplaceMeSequentialCommandGroup. */
|
||||
public ReplaceMeSequentialCommandGroup() {
|
||||
// Add your commands in the addCommands() call, e.g.
|
||||
// addCommands(new FooCommand(), new BarCommand());
|
||||
|
||||
@@ -6,9 +6,7 @@ package edu.wpi.first.wpilibj.commands.subsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.Subsystem;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMeSubsystem extends Subsystem {
|
||||
// Put methods for controlling this subsystem
|
||||
// here. Call these from Commands.
|
||||
|
||||
@@ -7,12 +7,8 @@ package edu.wpi.first.wpilibj.commands.subsystem2;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class ReplaceMeSubsystem extends SubsystemBase {
|
||||
/**
|
||||
* Creates a new ReplaceMeSubsystem.
|
||||
*/
|
||||
public ReplaceMeSubsystem() {
|
||||
|
||||
}
|
||||
/** Creates a new ReplaceMeSubsystem. */
|
||||
public ReplaceMeSubsystem() {}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
|
||||
@@ -6,13 +6,9 @@ package edu.wpi.first.wpilibj.commands.timed;
|
||||
|
||||
import edu.wpi.first.wpilibj.command.TimedCommand;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMeTimedCommand extends TimedCommand {
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public ReplaceMeTimedCommand(double timeout) {
|
||||
super(timeout);
|
||||
// Use requires() here to declare subsystem dependencies
|
||||
@@ -21,22 +17,18 @@ public class ReplaceMeTimedCommand extends TimedCommand {
|
||||
|
||||
// Called just before this Command runs the first time
|
||||
@Override
|
||||
protected void initialize() {
|
||||
}
|
||||
protected void initialize() {}
|
||||
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
@Override
|
||||
protected void execute() {
|
||||
}
|
||||
protected void execute() {}
|
||||
|
||||
// Called once after timeout
|
||||
@Override
|
||||
protected void end() {
|
||||
}
|
||||
protected void end() {}
|
||||
|
||||
// Called when another command which requires one or more of the same
|
||||
// subsystems is scheduled to run
|
||||
@Override
|
||||
protected void interrupted() {
|
||||
}
|
||||
protected void interrupted() {}
|
||||
}
|
||||
|
||||
@@ -11,9 +11,7 @@ import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
|
||||
// information, see:
|
||||
// https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
|
||||
public class ReplaceMeTrapezoidProfileCommand extends TrapezoidProfileCommand {
|
||||
/**
|
||||
* Creates a new ReplaceMeTrapezoidProfileCommand.
|
||||
*/
|
||||
/** Creates a new ReplaceMeTrapezoidProfileCommand. */
|
||||
public ReplaceMeTrapezoidProfileCommand() {
|
||||
super(
|
||||
// The motion profile to be executed
|
||||
|
||||
@@ -8,9 +8,7 @@ import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
|
||||
|
||||
public class ReplaceMeTrapezoidProfileSubsystem extends TrapezoidProfileSubsystem {
|
||||
/**
|
||||
* Creates a new ReplaceMeTrapezoidProfileSubsystem.
|
||||
*/
|
||||
/** Creates a new ReplaceMeTrapezoidProfileSubsystem. */
|
||||
public ReplaceMeTrapezoidProfileSubsystem() {
|
||||
super(
|
||||
// The constraints for the generated profiles
|
||||
|
||||
@@ -6,9 +6,7 @@ package edu.wpi.first.wpilibj.commands.trigger;
|
||||
|
||||
import edu.wpi.first.wpilibj.buttons.Trigger;
|
||||
|
||||
/**
|
||||
* Add your docs here.
|
||||
*/
|
||||
/** Add your docs here. */
|
||||
public class ReplaceMeTrigger extends Trigger {
|
||||
@Override
|
||||
public boolean get() {
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.addressableled;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.arcadedrive;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -10,8 +10,8 @@ import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with arcade steering.
|
||||
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with
|
||||
* arcade steering.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final PWMVictorSPX m_leftMotor = new PWMVictorSPX(0);
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.arcadedrivexboxcontroller;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -11,8 +11,8 @@ import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of the DifferentialDrive class.
|
||||
* Runs the motors with split arcade steering and an Xbox controller.
|
||||
* This is a demo program showing the use of the DifferentialDrive class. Runs the motors with split
|
||||
* arcade steering and an Xbox controller.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final PWMVictorSPX m_leftMotor = new PWMVictorSPX(0);
|
||||
@@ -25,7 +25,7 @@ public class Robot extends TimedRobot {
|
||||
// Drive with split arcade drive.
|
||||
// That means that the Y axis of the left stick moves forward
|
||||
// and backward, and the X of the right stick turns left and right.
|
||||
m_robotDrive.arcadeDrive(m_driverController.getY(Hand.kLeft),
|
||||
m_driverController.getX(Hand.kRight));
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getY(Hand.kLeft), m_driverController.getX(Hand.kRight));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.armbot;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be
|
||||
* declared globally (i.e. public static). Do not put anything functional in this class.
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
@@ -19,8 +19,8 @@ public final class Constants {
|
||||
public static final int kRightMotor1Port = 2;
|
||||
public static final int kRightMotor2Port = 3;
|
||||
|
||||
public static final int[] kLeftEncoderPorts = new int[]{0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[]{2, 3};
|
||||
public static final int[] kLeftEncoderPorts = new int[] {0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[] {2, 3};
|
||||
public static final boolean kLeftEncoderReversed = false;
|
||||
public static final boolean kRightEncoderReversed = true;
|
||||
|
||||
@@ -45,7 +45,7 @@ public final class Constants {
|
||||
public static final double kMaxVelocityRadPerSecond = 3;
|
||||
public static final double kMaxAccelerationRadPerSecSquared = 10;
|
||||
|
||||
public static final int[] kEncoderPorts = new int[]{4, 5};
|
||||
public static final int[] kEncoderPorts = new int[] {4, 5};
|
||||
public static final int kEncoderPPR = 256;
|
||||
public static final double kEncoderDistancePerPulse = 2.0 * Math.PI / kEncoderPPR;
|
||||
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,21 +46,16 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
m_robotContainer.disablePIDSubsystems();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -78,12 +73,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -96,13 +88,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -110,10 +98,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -4,24 +4,23 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.armbot;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.subsystems.ArmSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.subsystems.ArmSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.subsystems.DriveSubsystem;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||
* (including subsystems, commands, and button mappings) should be declared here.
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The robot's subsystems
|
||||
@@ -31,9 +30,7 @@ public class RobotContainer {
|
||||
// The driver's controller
|
||||
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
*/
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Configure the button bindings
|
||||
configureButtonBindings();
|
||||
@@ -43,37 +40,42 @@ public class RobotContainer {
|
||||
m_robotDrive.setDefaultCommand(
|
||||
// A split-stick arcade command, with forward/backward controlled by the left
|
||||
// hand, and turning controlled by the right.
|
||||
new RunCommand(() -> m_robotDrive
|
||||
.arcadeDrive(m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)), m_robotDrive));
|
||||
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a
|
||||
* {@link JoystickButton}.
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
|
||||
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
|
||||
new JoystickButton(m_driverController, Button.kA.value)
|
||||
.whenPressed(() -> {
|
||||
m_robotArm.setGoal(2);
|
||||
m_robotArm.enable();
|
||||
}, m_robotArm);
|
||||
.whenPressed(
|
||||
() -> {
|
||||
m_robotArm.setGoal(2);
|
||||
m_robotArm.enable();
|
||||
},
|
||||
m_robotArm);
|
||||
|
||||
// Move the arm to neutral position when the 'B' button is pressed.
|
||||
new JoystickButton(m_driverController, Button.kB.value)
|
||||
.whenPressed(() -> {
|
||||
m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
|
||||
m_robotArm.enable();
|
||||
}, m_robotArm);
|
||||
.whenPressed(
|
||||
() -> {
|
||||
m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
|
||||
m_robotArm.enable();
|
||||
},
|
||||
m_robotArm);
|
||||
|
||||
// Disable the arm controller when Y is pressed.
|
||||
new JoystickButton(m_driverController, Button.kY.value)
|
||||
.whenPressed(m_robotArm::disable);
|
||||
new JoystickButton(m_driverController, Button.kY.value).whenPressed(m_robotArm::disable);
|
||||
|
||||
// Drive at half speed when the bumper is held
|
||||
new JoystickButton(m_driverController, Button.kBumperRight.value)
|
||||
@@ -82,8 +84,8 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
/**
|
||||
* Disables all ProfiledPIDSubsystem and PIDSubsystem instances. This
|
||||
* should be called on robot disable to prevent integral windup.
|
||||
* Disables all ProfiledPIDSubsystem and PIDSubsystem instances. This should be called on robot
|
||||
* disable to prevent integral windup.
|
||||
*/
|
||||
public void disablePIDSubsystems() {
|
||||
m_robotArm.disable();
|
||||
|
||||
@@ -8,28 +8,31 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.controller.ArmFeedforward;
|
||||
import edu.wpi.first.wpilibj.controller.ProfiledPIDController;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.ArmConstants;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.ProfiledPIDSubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.ArmConstants;
|
||||
|
||||
/**
|
||||
* A robot arm subsystem that moves with a motion profile.
|
||||
*/
|
||||
/** A robot arm subsystem that moves with a motion profile. */
|
||||
public class ArmSubsystem extends ProfiledPIDSubsystem {
|
||||
private final PWMVictorSPX m_motor = new PWMVictorSPX(ArmConstants.kMotorPort);
|
||||
private final Encoder m_encoder =
|
||||
new Encoder(ArmConstants.kEncoderPorts[0], ArmConstants.kEncoderPorts[1]);
|
||||
private final ArmFeedforward m_feedforward =
|
||||
new ArmFeedforward(ArmConstants.kSVolts, ArmConstants.kCosVolts,
|
||||
ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
|
||||
new ArmFeedforward(
|
||||
ArmConstants.kSVolts, ArmConstants.kCosVolts,
|
||||
ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
|
||||
|
||||
/**
|
||||
* Create a new ArmSubsystem.
|
||||
*/
|
||||
/** Create a new ArmSubsystem. */
|
||||
public ArmSubsystem() {
|
||||
super(new ProfiledPIDController(ArmConstants.kP, 0, 0, new TrapezoidProfile.Constraints(
|
||||
ArmConstants.kMaxVelocityRadPerSecond, ArmConstants.kMaxAccelerationRadPerSecSquared)), 0);
|
||||
super(
|
||||
new ProfiledPIDController(
|
||||
ArmConstants.kP,
|
||||
0,
|
||||
0,
|
||||
new TrapezoidProfile.Constraints(
|
||||
ArmConstants.kMaxVelocityRadPerSecond,
|
||||
ArmConstants.kMaxAccelerationRadPerSecSquared)),
|
||||
0);
|
||||
m_encoder.setDistancePerPulse(ArmConstants.kEncoderDistancePerPulse);
|
||||
// Start arm at rest in neutral position
|
||||
setGoal(ArmConstants.kArmOffsetRads);
|
||||
|
||||
@@ -8,37 +8,40 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final SpeedControllerGroup m_leftMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
|
||||
// The motors on the right side of the drive.
|
||||
private final SpeedControllerGroup m_rightMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
|
||||
// The robot's drive
|
||||
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
|
||||
|
||||
// The left-side drive encoder
|
||||
private final Encoder m_leftEncoder =
|
||||
new Encoder(DriveConstants.kLeftEncoderPorts[0], DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kLeftEncoderPorts[0],
|
||||
DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
|
||||
// The right-side drive encoder
|
||||
private final Encoder m_rightEncoder =
|
||||
new Encoder(DriveConstants.kRightEncoderPorts[0], DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kRightEncoderPorts[0],
|
||||
DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
*/
|
||||
/** Creates a new DriveSubsystem. */
|
||||
public DriveSubsystem() {
|
||||
// Sets the distance per pulse for the encoders
|
||||
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
@@ -55,9 +58,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_drive.arcadeDrive(fwd, rot);
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the drive encoders to currently read a position of 0.
|
||||
*/
|
||||
/** Resets the drive encoders to currently read a position of 0. */
|
||||
public void resetEncoders() {
|
||||
m_leftEncoder.reset();
|
||||
m_rightEncoder.reset();
|
||||
@@ -91,7 +92,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
* @param maxOutput the maximum output to which the drive will be constrained
|
||||
*/
|
||||
|
||||
@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.armbotoffboard;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be
|
||||
* declared globally (i.e. public static). Do not put anything functional in this class.
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
@@ -19,8 +19,8 @@ public final class Constants {
|
||||
public static final int kRightMotor1Port = 2;
|
||||
public static final int kRightMotor2Port = 3;
|
||||
|
||||
public static final int[] kLeftEncoderPorts = new int[]{0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[]{2, 3};
|
||||
public static final int[] kLeftEncoderPorts = new int[] {0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[] {2, 3};
|
||||
public static final boolean kLeftEncoderReversed = false;
|
||||
public static final boolean kRightEncoderReversed = true;
|
||||
|
||||
|
||||
@@ -24,8 +24,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param port The port for the controller.
|
||||
*/
|
||||
@SuppressWarnings("PMD.UnusedFormalParameter")
|
||||
public ExampleSmartMotorController(int port) {
|
||||
}
|
||||
public ExampleSmartMotorController(int port) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the PID gains of the smart controller.
|
||||
@@ -34,8 +33,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param ki The integral gain.
|
||||
* @param kd The derivative gain.
|
||||
*/
|
||||
public void setPID(double kp, double ki, double kd) {
|
||||
}
|
||||
public void setPID(double kp, double ki, double kd) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the setpoint of the smart controller in PID mode.
|
||||
@@ -44,16 +42,14 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param setpoint The controller setpoint.
|
||||
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
|
||||
*/
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {
|
||||
}
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
|
||||
|
||||
/**
|
||||
* Places this motor controller in follower mode.
|
||||
*
|
||||
* @param leader The leader to follow.
|
||||
*/
|
||||
public void follow(ExampleSmartMotorController leader) {
|
||||
}
|
||||
public void follow(ExampleSmartMotorController leader) {}
|
||||
|
||||
/**
|
||||
* Returns the encoder distance.
|
||||
@@ -73,15 +69,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the encoder to zero distance.
|
||||
*/
|
||||
public void resetEncoder() {
|
||||
}
|
||||
/** Resets the encoder to zero distance. */
|
||||
public void resetEncoder() {}
|
||||
|
||||
@Override
|
||||
public void set(double speed) {
|
||||
}
|
||||
public void set(double speed) {}
|
||||
|
||||
@Override
|
||||
public double get() {
|
||||
@@ -89,9 +81,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setInverted(boolean isInverted) {
|
||||
|
||||
}
|
||||
public void setInverted(boolean isInverted) {}
|
||||
|
||||
@Override
|
||||
public boolean getInverted() {
|
||||
@@ -99,14 +89,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disable() {
|
||||
}
|
||||
public void disable() {}
|
||||
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
}
|
||||
public void stopMotor() {}
|
||||
|
||||
@Override
|
||||
public void pidWrite(double output) {
|
||||
}
|
||||
public void pidWrite(double output) {}
|
||||
}
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,20 +46,14 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -77,12 +71,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -95,13 +86,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -109,10 +96,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -4,24 +4,23 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.armbotoffboard;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.ArmSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.ArmSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.DriveSubsystem;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||
* (including subsystems, commands, and button mappings) should be declared here.
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The robot's subsystems
|
||||
@@ -31,9 +30,7 @@ public class RobotContainer {
|
||||
// The driver's controller
|
||||
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
*/
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Configure the button bindings
|
||||
configureButtonBindings();
|
||||
@@ -43,17 +40,19 @@ public class RobotContainer {
|
||||
m_robotDrive.setDefaultCommand(
|
||||
// A split-stick arcade command, with forward/backward controlled by the left
|
||||
// hand, and turning controlled by the right.
|
||||
new RunCommand(() -> m_robotDrive
|
||||
.arcadeDrive(m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)), m_robotDrive));
|
||||
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a
|
||||
* {@link JoystickButton}.
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
|
||||
@@ -71,7 +70,6 @@ public class RobotContainer {
|
||||
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||
*
|
||||
|
||||
@@ -5,29 +5,26 @@
|
||||
package edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.ArmFeedforward;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;
|
||||
|
||||
/**
|
||||
* A robot arm subsystem that moves with a motion profile.
|
||||
*/
|
||||
/** A robot arm subsystem that moves with a motion profile. */
|
||||
public class ArmSubsystem extends TrapezoidProfileSubsystem {
|
||||
private final ExampleSmartMotorController m_motor =
|
||||
new ExampleSmartMotorController(ArmConstants.kMotorPort);
|
||||
private final ArmFeedforward m_feedforward =
|
||||
new ArmFeedforward(ArmConstants.kSVolts, ArmConstants.kCosVolts,
|
||||
ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
|
||||
new ArmFeedforward(
|
||||
ArmConstants.kSVolts, ArmConstants.kCosVolts,
|
||||
ArmConstants.kVVoltSecondPerRad, ArmConstants.kAVoltSecondSquaredPerRad);
|
||||
|
||||
/**
|
||||
* Create a new ArmSubsystem.
|
||||
*/
|
||||
/** Create a new ArmSubsystem. */
|
||||
public ArmSubsystem() {
|
||||
super(new TrapezoidProfile.Constraints(ArmConstants.kMaxVelocityRadPerSecond,
|
||||
ArmConstants.kMaxAccelerationRadPerSecSquared),
|
||||
ArmConstants.kArmOffsetRads);
|
||||
super(
|
||||
new TrapezoidProfile.Constraints(
|
||||
ArmConstants.kMaxVelocityRadPerSecond, ArmConstants.kMaxAccelerationRadPerSecSquared),
|
||||
ArmConstants.kArmOffsetRads);
|
||||
m_motor.setPID(ArmConstants.kP, 0, 0);
|
||||
}
|
||||
|
||||
@@ -36,7 +33,7 @@ public class ArmSubsystem extends TrapezoidProfileSubsystem {
|
||||
// Calculate the feedforward from the sepoint
|
||||
double feedforward = m_feedforward.calculate(setpoint.position, setpoint.velocity);
|
||||
// Add the feedforward to the PID output to get the motor output
|
||||
m_motor.setSetpoint(ExampleSmartMotorController.PIDMode.kPosition, setpoint.position,
|
||||
feedforward / 12.0);
|
||||
m_motor.setSetpoint(
|
||||
ExampleSmartMotorController.PIDMode.kPosition, setpoint.position, feedforward / 12.0);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -8,37 +8,40 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final SpeedControllerGroup m_leftMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
|
||||
// The motors on the right side of the drive.
|
||||
private final SpeedControllerGroup m_rightMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
|
||||
// The robot's drive
|
||||
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
|
||||
|
||||
// The left-side drive encoder
|
||||
private final Encoder m_leftEncoder =
|
||||
new Encoder(DriveConstants.kLeftEncoderPorts[0], DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kLeftEncoderPorts[0],
|
||||
DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
|
||||
// The right-side drive encoder
|
||||
private final Encoder m_rightEncoder =
|
||||
new Encoder(DriveConstants.kRightEncoderPorts[0], DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kRightEncoderPorts[0],
|
||||
DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
*/
|
||||
/** Creates a new DriveSubsystem. */
|
||||
public DriveSubsystem() {
|
||||
// Sets the distance per pulse for the encoders
|
||||
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
@@ -55,9 +58,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_drive.arcadeDrive(fwd, rot);
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the drive encoders to currently read a position of 0.
|
||||
*/
|
||||
/** Resets the drive encoders to currently read a position of 0. */
|
||||
public void resetEncoders() {
|
||||
m_leftEncoder.reset();
|
||||
m_rightEncoder.reset();
|
||||
@@ -91,7 +92,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
* @param maxOutput the maximum output to which the drive will be constrained
|
||||
*/
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.armsimulation;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -10,17 +10,15 @@ import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate the use of elevator simulation with existing code.
|
||||
*/
|
||||
/** This is a sample program to demonstrate the use of elevator simulation with existing code. */
|
||||
public class Robot extends TimedRobot {
|
||||
private static final int kMotorPort = 0;
|
||||
private static final int kEncoderAChannel = 0;
|
||||
@@ -49,16 +47,18 @@ public class Robot extends TimedRobot {
|
||||
private static final double m_armLength = Units.inchesToMeters(30);
|
||||
// This arm sim represents an arm that can travel from -180 degrees (rotated straight backwards)
|
||||
// to 0 degrees (rotated straight forwards).
|
||||
private final SingleJointedArmSim m_armSim = new SingleJointedArmSim(m_armGearbox,
|
||||
m_armReduction,
|
||||
SingleJointedArmSim.estimateMOI(m_armLength, m_armMass),
|
||||
m_armLength,
|
||||
Units.degreesToRadians(-180),
|
||||
Units.degreesToRadians(0),
|
||||
m_armMass,
|
||||
true,
|
||||
VecBuilder.fill(Units.degreesToRadians(0.5)) // Add noise with a std-dev of 0.5 degrees
|
||||
);
|
||||
private final SingleJointedArmSim m_armSim =
|
||||
new SingleJointedArmSim(
|
||||
m_armGearbox,
|
||||
m_armReduction,
|
||||
SingleJointedArmSim.estimateMOI(m_armLength, m_armMass),
|
||||
m_armLength,
|
||||
Units.degreesToRadians(-180),
|
||||
Units.degreesToRadians(0),
|
||||
m_armMass,
|
||||
true,
|
||||
VecBuilder.fill(Units.degreesToRadians(0.5)) // Add noise with a std-dev of 0.5 degrees
|
||||
);
|
||||
private final EncoderSim m_encoderSim = new EncoderSim(m_encoder);
|
||||
|
||||
@Override
|
||||
@@ -78,7 +78,8 @@ public class Robot extends TimedRobot {
|
||||
// Finally, we set our simulated encoder's readings and simulated battery voltage
|
||||
m_encoderSim.setDistance(m_armSim.getAngleRads());
|
||||
// SimBattery estimates loaded battery voltages
|
||||
RoboRioSim.setVInVoltage(BatterySim.calculateDefaultBatteryLoadedVoltage(m_armSim.getCurrentDrawAmps()));
|
||||
RoboRioSim.setVInVoltage(
|
||||
BatterySim.calculateDefaultBatteryLoadedVoltage(m_armSim.getCurrentDrawAmps()));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.axiscamera;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -4,63 +4,61 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.axiscamera;
|
||||
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Point;
|
||||
import org.opencv.core.Scalar;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
|
||||
import edu.wpi.cscore.AxisCamera;
|
||||
import edu.wpi.cscore.CvSink;
|
||||
import edu.wpi.cscore.CvSource;
|
||||
import edu.wpi.first.cameraserver.CameraServer;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import org.opencv.core.Mat;
|
||||
import org.opencv.core.Point;
|
||||
import org.opencv.core.Scalar;
|
||||
import org.opencv.imgproc.Imgproc;
|
||||
|
||||
/**
|
||||
* This is a demo program showing the use of OpenCV to do vision processing. The
|
||||
* image is acquired from the Axis camera, then a rectangle is put on the image
|
||||
* and sent to the dashboard. OpenCV has many methods for different types of
|
||||
* processing.
|
||||
* This is a demo program showing the use of OpenCV to do vision processing. The image is acquired
|
||||
* from the Axis camera, then a rectangle is put on the image and sent to the dashboard. OpenCV has
|
||||
* many methods for different types of processing.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
Thread m_visionThread;
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
m_visionThread = new Thread(() -> {
|
||||
// Get the Axis camera from CameraServer
|
||||
AxisCamera camera
|
||||
= CameraServer.getInstance().addAxisCamera("axis-camera.local");
|
||||
// Set the resolution
|
||||
camera.setResolution(640, 480);
|
||||
m_visionThread =
|
||||
new Thread(
|
||||
() -> {
|
||||
// Get the Axis camera from CameraServer
|
||||
AxisCamera camera = CameraServer.getInstance().addAxisCamera("axis-camera.local");
|
||||
// Set the resolution
|
||||
camera.setResolution(640, 480);
|
||||
|
||||
// Get a CvSink. This will capture Mats from the camera
|
||||
CvSink cvSink = CameraServer.getInstance().getVideo();
|
||||
// Setup a CvSource. This will send images back to the Dashboard
|
||||
CvSource outputStream
|
||||
= CameraServer.getInstance().putVideo("Rectangle", 640, 480);
|
||||
// Get a CvSink. This will capture Mats from the camera
|
||||
CvSink cvSink = CameraServer.getInstance().getVideo();
|
||||
// Setup a CvSource. This will send images back to the Dashboard
|
||||
CvSource outputStream = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
|
||||
|
||||
// Mats are very memory expensive. Lets reuse this Mat.
|
||||
Mat mat = new Mat();
|
||||
// Mats are very memory expensive. Lets reuse this Mat.
|
||||
Mat mat = new Mat();
|
||||
|
||||
// This cannot be 'true'. The program will never exit if it is. This
|
||||
// lets the robot stop this thread when restarting robot code or
|
||||
// deploying.
|
||||
while (!Thread.interrupted()) {
|
||||
// Tell the CvSink to grab a frame from the camera and put it
|
||||
// in the source mat. If there is an error notify the output.
|
||||
if (cvSink.grabFrame(mat) == 0) {
|
||||
// Send the output the error.
|
||||
outputStream.notifyError(cvSink.getError());
|
||||
// skip the rest of the current iteration
|
||||
continue;
|
||||
}
|
||||
// Put a rectangle on the image
|
||||
Imgproc.rectangle(mat, new Point(100, 100), new Point(400, 400),
|
||||
new Scalar(255, 255, 255), 5);
|
||||
// Give the output stream a new image to display
|
||||
outputStream.putFrame(mat);
|
||||
}
|
||||
});
|
||||
// This cannot be 'true'. The program will never exit if it is. This
|
||||
// lets the robot stop this thread when restarting robot code or
|
||||
// deploying.
|
||||
while (!Thread.interrupted()) {
|
||||
// Tell the CvSink to grab a frame from the camera and put it
|
||||
// in the source mat. If there is an error notify the output.
|
||||
if (cvSink.grabFrame(mat) == 0) {
|
||||
// Send the output the error.
|
||||
outputStream.notifyError(cvSink.getError());
|
||||
// skip the rest of the current iteration
|
||||
continue;
|
||||
}
|
||||
// Put a rectangle on the image
|
||||
Imgproc.rectangle(
|
||||
mat, new Point(100, 100), new Point(400, 400), new Scalar(255, 255, 255), 5);
|
||||
// Give the output stream a new image to display
|
||||
outputStream.putFrame(mat);
|
||||
}
|
||||
});
|
||||
m_visionThread.setDaemon(true);
|
||||
m_visionThread.start();
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.canpdp;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -16,9 +16,7 @@ import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveOdometry;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
|
||||
/**
|
||||
* Represents a differential drive style drivetrain.
|
||||
*/
|
||||
/** Represents a differential drive style drivetrain. */
|
||||
public class Drivetrain {
|
||||
public static final double kMaxSpeed = 3.0; // meters per second
|
||||
public static final double kMaxAngularSpeed = 2 * Math.PI; // one rotation per second
|
||||
@@ -35,18 +33,18 @@ public class Drivetrain {
|
||||
private final Encoder m_leftEncoder = new Encoder(0, 1);
|
||||
private final Encoder m_rightEncoder = new Encoder(2, 3);
|
||||
|
||||
private final SpeedControllerGroup m_leftGroup
|
||||
= new SpeedControllerGroup(m_leftLeader, m_leftFollower);
|
||||
private final SpeedControllerGroup m_rightGroup
|
||||
= new SpeedControllerGroup(m_rightLeader, m_rightFollower);
|
||||
private final SpeedControllerGroup m_leftGroup =
|
||||
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
|
||||
private final SpeedControllerGroup m_rightGroup =
|
||||
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
|
||||
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(0);
|
||||
|
||||
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
|
||||
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
|
||||
|
||||
private final DifferentialDriveKinematics m_kinematics
|
||||
= new DifferentialDriveKinematics(kTrackWidth);
|
||||
private final DifferentialDriveKinematics m_kinematics =
|
||||
new DifferentialDriveKinematics(kTrackWidth);
|
||||
|
||||
private final DifferentialDriveOdometry m_odometry;
|
||||
|
||||
@@ -54,8 +52,8 @@ public class Drivetrain {
|
||||
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
|
||||
|
||||
/**
|
||||
* Constructs a differential drive object.
|
||||
* Sets the encoder distance per pulse and resets the gyro.
|
||||
* Constructs a differential drive object. Sets the encoder distance per pulse and resets the
|
||||
* gyro.
|
||||
*/
|
||||
public Drivetrain() {
|
||||
m_gyro.reset();
|
||||
@@ -81,10 +79,10 @@ public class Drivetrain {
|
||||
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
|
||||
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
|
||||
|
||||
final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(),
|
||||
speeds.leftMetersPerSecond);
|
||||
final double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(),
|
||||
speeds.rightMetersPerSecond);
|
||||
final double leftOutput =
|
||||
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
|
||||
final double rightOutput =
|
||||
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
|
||||
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
|
||||
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
|
||||
}
|
||||
@@ -93,7 +91,7 @@ public class Drivetrain {
|
||||
* Drives the robot with the given linear velocity and angular velocity.
|
||||
*
|
||||
* @param xSpeed Linear velocity in m/s.
|
||||
* @param rot Angular velocity in rad/s.
|
||||
* @param rot Angular velocity in rad/s.
|
||||
*/
|
||||
@SuppressWarnings("ParameterName")
|
||||
public void drive(double xSpeed, double rot) {
|
||||
@@ -101,11 +99,9 @@ public class Drivetrain {
|
||||
setSpeeds(wheelSpeeds);
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates the field-relative position.
|
||||
*/
|
||||
/** Updates the field-relative position. */
|
||||
public void updateOdometry() {
|
||||
m_odometry.update(m_gyro.getRotation2d(), m_leftEncoder.getDistance(),
|
||||
m_rightEncoder.getDistance());
|
||||
m_odometry.update(
|
||||
m_gyro.getRotation2d(), m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.differentialdrivebot;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -17,7 +17,6 @@ public class Robot extends TimedRobot {
|
||||
private final SlewRateLimiter m_speedLimiter = new SlewRateLimiter(3);
|
||||
private final SlewRateLimiter m_rotLimiter = new SlewRateLimiter(3);
|
||||
|
||||
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
teleopPeriodic();
|
||||
@@ -29,8 +28,7 @@ public class Robot extends TimedRobot {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// negative values when we push forward.
|
||||
final var xSpeed =
|
||||
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft))
|
||||
* Drivetrain.kMaxSpeed;
|
||||
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
|
||||
|
||||
// Get the rate of angular rotation. We are inverting this because we want a
|
||||
// positive value when we pull to the left (remember, CCW is positive in
|
||||
|
||||
@@ -13,6 +13,7 @@ import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.estimator.DifferentialDrivePoseEstimator;
|
||||
import edu.wpi.first.wpilibj.examples.swervesdriveposeestimator.ExampleGlobalMeasurementSensor;
|
||||
import edu.wpi.first.wpilibj.geometry.Pose2d;
|
||||
import edu.wpi.first.wpilibj.kinematics.ChassisSpeeds;
|
||||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
|
||||
@@ -20,11 +21,7 @@ import edu.wpi.first.wpilibj.kinematics.DifferentialDriveWheelSpeeds;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.swervesdriveposeestimator.ExampleGlobalMeasurementSensor;
|
||||
|
||||
/**
|
||||
* Represents a differential drive style drivetrain.
|
||||
*/
|
||||
/** Represents a differential drive style drivetrain. */
|
||||
public class Drivetrain {
|
||||
public static final double kMaxSpeed = 3.0; // meters per second
|
||||
public static final double kMaxAngularSpeed = 2 * Math.PI; // one rotation per second
|
||||
@@ -41,34 +38,35 @@ public class Drivetrain {
|
||||
private final Encoder m_leftEncoder = new Encoder(0, 1);
|
||||
private final Encoder m_rightEncoder = new Encoder(2, 3);
|
||||
|
||||
private final SpeedControllerGroup m_leftGroup
|
||||
= new SpeedControllerGroup(m_leftLeader, m_leftFollower);
|
||||
private final SpeedControllerGroup m_rightGroup
|
||||
= new SpeedControllerGroup(m_rightLeader, m_rightFollower);
|
||||
private final SpeedControllerGroup m_leftGroup =
|
||||
new SpeedControllerGroup(m_leftLeader, m_leftFollower);
|
||||
private final SpeedControllerGroup m_rightGroup =
|
||||
new SpeedControllerGroup(m_rightLeader, m_rightFollower);
|
||||
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(0);
|
||||
|
||||
private final PIDController m_leftPIDController = new PIDController(1, 0, 0);
|
||||
private final PIDController m_rightPIDController = new PIDController(1, 0, 0);
|
||||
|
||||
private final DifferentialDriveKinematics m_kinematics
|
||||
= new DifferentialDriveKinematics(kTrackWidth);
|
||||
private final DifferentialDriveKinematics m_kinematics =
|
||||
new DifferentialDriveKinematics(kTrackWidth);
|
||||
|
||||
/* Here we use DifferentialDrivePoseEstimator so that we can fuse odometry readings. The
|
||||
numbers used below are robot specific, and should be tuned. */
|
||||
private final DifferentialDrivePoseEstimator m_poseEstimator = new DifferentialDrivePoseEstimator(
|
||||
m_gyro.getRotation2d(),
|
||||
new Pose2d(),
|
||||
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5), 0.01, 0.01),
|
||||
VecBuilder.fill(0.02, 0.02, Units.degreesToRadians(1)),
|
||||
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
|
||||
private final DifferentialDrivePoseEstimator m_poseEstimator =
|
||||
new DifferentialDrivePoseEstimator(
|
||||
m_gyro.getRotation2d(),
|
||||
new Pose2d(),
|
||||
VecBuilder.fill(0.05, 0.05, Units.degreesToRadians(5), 0.01, 0.01),
|
||||
VecBuilder.fill(0.02, 0.02, Units.degreesToRadians(1)),
|
||||
VecBuilder.fill(0.5, 0.5, Units.degreesToRadians(30)));
|
||||
|
||||
// Gains are for example purposes only - must be determined for your own robot!
|
||||
private final SimpleMotorFeedforward m_feedforward = new SimpleMotorFeedforward(1, 3);
|
||||
|
||||
/**
|
||||
* Constructs a differential drive object.
|
||||
* Sets the encoder distance per pulse and resets the gyro.
|
||||
* Constructs a differential drive object. Sets the encoder distance per pulse and resets the
|
||||
* gyro.
|
||||
*/
|
||||
public Drivetrain() {
|
||||
m_gyro.reset();
|
||||
@@ -92,10 +90,10 @@ public class Drivetrain {
|
||||
final double leftFeedforward = m_feedforward.calculate(speeds.leftMetersPerSecond);
|
||||
final double rightFeedforward = m_feedforward.calculate(speeds.rightMetersPerSecond);
|
||||
|
||||
final double leftOutput = m_leftPIDController.calculate(m_leftEncoder.getRate(),
|
||||
speeds.leftMetersPerSecond);
|
||||
final double rightOutput = m_rightPIDController.calculate(m_rightEncoder.getRate(),
|
||||
speeds.rightMetersPerSecond);
|
||||
final double leftOutput =
|
||||
m_leftPIDController.calculate(m_leftEncoder.getRate(), speeds.leftMetersPerSecond);
|
||||
final double rightOutput =
|
||||
m_rightPIDController.calculate(m_rightEncoder.getRate(), speeds.rightMetersPerSecond);
|
||||
m_leftGroup.setVoltage(leftOutput + leftFeedforward);
|
||||
m_rightGroup.setVoltage(rightOutput + rightFeedforward);
|
||||
}
|
||||
@@ -104,7 +102,7 @@ public class Drivetrain {
|
||||
* Drives the robot with the given linear velocity and angular velocity.
|
||||
*
|
||||
* @param xSpeed Linear velocity in m/s.
|
||||
* @param rot Angular velocity in rad/s.
|
||||
* @param rot Angular velocity in rad/s.
|
||||
*/
|
||||
@SuppressWarnings("ParameterName")
|
||||
public void drive(double xSpeed, double rot) {
|
||||
@@ -112,13 +110,13 @@ public class Drivetrain {
|
||||
setSpeeds(wheelSpeeds);
|
||||
}
|
||||
|
||||
/**
|
||||
* Updates the field-relative position.
|
||||
*/
|
||||
/** Updates the field-relative position. */
|
||||
public void updateOdometry() {
|
||||
m_poseEstimator.update(m_gyro.getRotation2d(),
|
||||
m_poseEstimator.update(
|
||||
m_gyro.getRotation2d(),
|
||||
new DifferentialDriveWheelSpeeds(m_leftEncoder.getRate(), m_rightEncoder.getRate()),
|
||||
m_leftEncoder.getDistance(), m_rightEncoder.getDistance());
|
||||
m_leftEncoder.getDistance(),
|
||||
m_rightEncoder.getDistance());
|
||||
|
||||
// Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
|
||||
// a real robot, this must be calculated based either on latency or timestamps.
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.differentialdriveposeestimator;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -17,7 +17,6 @@ public class Robot extends TimedRobot {
|
||||
private final SlewRateLimiter m_speedLimiter = new SlewRateLimiter(3);
|
||||
private final SlewRateLimiter m_rotLimiter = new SlewRateLimiter(3);
|
||||
|
||||
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
teleopPeriodic();
|
||||
@@ -29,8 +28,7 @@ public class Robot extends TimedRobot {
|
||||
// Get the x speed. We are inverting this because Xbox controllers return
|
||||
// negative values when we push forward.
|
||||
final var xSpeed =
|
||||
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft))
|
||||
* Drivetrain.kMaxSpeed;
|
||||
-m_speedLimiter.calculate(m_controller.getY(GenericHID.Hand.kLeft)) * Drivetrain.kMaxSpeed;
|
||||
|
||||
// Get the rate of angular rotation. We are inverting this because we want a
|
||||
// positive value when we pull to the left (remember, CCW is positive in
|
||||
|
||||
@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be
|
||||
* declared globally (i.e. public static). Do not put anything functional in this class.
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
|
||||
@@ -24,8 +24,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param port The port for the controller.
|
||||
*/
|
||||
@SuppressWarnings("PMD.UnusedFormalParameter")
|
||||
public ExampleSmartMotorController(int port) {
|
||||
}
|
||||
public ExampleSmartMotorController(int port) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the PID gains of the smart controller.
|
||||
@@ -34,8 +33,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param ki The integral gain.
|
||||
* @param kd The derivative gain.
|
||||
*/
|
||||
public void setPID(double kp, double ki, double kd) {
|
||||
}
|
||||
public void setPID(double kp, double ki, double kd) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the setpoint of the smart controller in PID mode.
|
||||
@@ -44,16 +42,14 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param setpoint The controller setpoint.
|
||||
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
|
||||
*/
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {
|
||||
}
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
|
||||
|
||||
/**
|
||||
* Places this motor controller in follower mode.
|
||||
*
|
||||
* @param leader The leader to follow.
|
||||
*/
|
||||
public void follow(ExampleSmartMotorController leader) {
|
||||
}
|
||||
public void follow(ExampleSmartMotorController leader) {}
|
||||
|
||||
/**
|
||||
* Returns the encoder distance.
|
||||
@@ -73,15 +69,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the encoder to zero distance.
|
||||
*/
|
||||
public void resetEncoder() {
|
||||
}
|
||||
/** Resets the encoder to zero distance. */
|
||||
public void resetEncoder() {}
|
||||
|
||||
@Override
|
||||
public void set(double speed) {
|
||||
}
|
||||
public void set(double speed) {}
|
||||
|
||||
@Override
|
||||
public double get() {
|
||||
@@ -89,9 +81,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setInverted(boolean isInverted) {
|
||||
|
||||
}
|
||||
public void setInverted(boolean isInverted) {}
|
||||
|
||||
@Override
|
||||
public boolean getInverted() {
|
||||
@@ -99,14 +89,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disable() {
|
||||
}
|
||||
public void disable() {}
|
||||
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
}
|
||||
public void stopMotor() {}
|
||||
|
||||
@Override
|
||||
public void pidWrite(double output) {
|
||||
}
|
||||
public void pidWrite(double output) {}
|
||||
}
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,20 +46,14 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -77,12 +71,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -95,13 +86,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -109,10 +96,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -4,8 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands.DriveDistanceProfiled;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
@@ -13,18 +19,11 @@ import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands.DriveDistanceProfiled;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||
* (including subsystems, commands, and button mappings) should be declared here.
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The robot's subsystems
|
||||
@@ -33,9 +32,7 @@ public class RobotContainer {
|
||||
// The driver's controller
|
||||
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
*/
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Configure the button bindings
|
||||
configureButtonBindings();
|
||||
@@ -45,17 +42,19 @@ public class RobotContainer {
|
||||
m_robotDrive.setDefaultCommand(
|
||||
// A split-stick arcade command, with forward/backward controlled by the left
|
||||
// hand, and turning controlled by the right.
|
||||
new RunCommand(() -> m_robotDrive
|
||||
.arcadeDrive(m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)), m_robotDrive));
|
||||
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a
|
||||
* {@link JoystickButton}.
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of 10 seconds
|
||||
@@ -66,19 +65,17 @@ public class RobotContainer {
|
||||
new JoystickButton(m_driverController, Button.kB.value)
|
||||
.whenPressed(
|
||||
new TrapezoidProfileCommand(
|
||||
new TrapezoidProfile(
|
||||
// Limit the max acceleration and velocity
|
||||
new TrapezoidProfile.Constraints(
|
||||
DriveConstants.kMaxSpeedMetersPerSecond,
|
||||
DriveConstants.kMaxAccelerationMetersPerSecondSquared),
|
||||
// End at desired position in meters; implicitly starts at 0
|
||||
new TrapezoidProfile.State(3, 0)),
|
||||
// Pipe the profile state to the drive
|
||||
setpointState -> m_robotDrive.setDriveStates(
|
||||
setpointState,
|
||||
setpointState),
|
||||
// Require the drive
|
||||
m_robotDrive)
|
||||
new TrapezoidProfile(
|
||||
// Limit the max acceleration and velocity
|
||||
new TrapezoidProfile.Constraints(
|
||||
DriveConstants.kMaxSpeedMetersPerSecond,
|
||||
DriveConstants.kMaxAccelerationMetersPerSecondSquared),
|
||||
// End at desired position in meters; implicitly starts at 0
|
||||
new TrapezoidProfile.State(3, 0)),
|
||||
// Pipe the profile state to the drive
|
||||
setpointState -> m_robotDrive.setDriveStates(setpointState, setpointState),
|
||||
// Require the drive
|
||||
m_robotDrive)
|
||||
.beforeStarting(m_robotDrive::resetEncoders)
|
||||
.withTimeout(10));
|
||||
|
||||
@@ -88,7 +85,6 @@ public class RobotContainer {
|
||||
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||
*
|
||||
|
||||
@@ -4,15 +4,12 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
|
||||
|
||||
/**
|
||||
* Drives a set distance using a motion profile.
|
||||
*/
|
||||
/** Drives a set distance using a motion profile. */
|
||||
public class DriveDistanceProfiled extends TrapezoidProfileCommand {
|
||||
/**
|
||||
* Creates a new DriveDistanceProfiled command.
|
||||
@@ -24,8 +21,9 @@ public class DriveDistanceProfiled extends TrapezoidProfileCommand {
|
||||
super(
|
||||
new TrapezoidProfile(
|
||||
// Limit the max acceleration and velocity
|
||||
new TrapezoidProfile.Constraints(DriveConstants.kMaxSpeedMetersPerSecond,
|
||||
DriveConstants.kMaxAccelerationMetersPerSecondSquared),
|
||||
new TrapezoidProfile.Constraints(
|
||||
DriveConstants.kMaxSpeedMetersPerSecond,
|
||||
DriveConstants.kMaxAccelerationMetersPerSecondSquared),
|
||||
// End at desired position in meters; implicitly starts at 0
|
||||
new TrapezoidProfile.State(meters, 0)),
|
||||
// Pipe the profile state to the drive
|
||||
|
||||
@@ -6,11 +6,10 @@ package edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
@@ -27,16 +26,15 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
new ExampleSmartMotorController(DriveConstants.kRightMotor2Port);
|
||||
|
||||
private final SimpleMotorFeedforward m_feedforward =
|
||||
new SimpleMotorFeedforward(DriveConstants.ksVolts,
|
||||
DriveConstants.kvVoltSecondsPerMeter,
|
||||
DriveConstants.kaVoltSecondsSquaredPerMeter);
|
||||
new SimpleMotorFeedforward(
|
||||
DriveConstants.ksVolts,
|
||||
DriveConstants.kvVoltSecondsPerMeter,
|
||||
DriveConstants.kaVoltSecondsSquaredPerMeter);
|
||||
|
||||
// The robot's drive
|
||||
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftLeader, m_rightLeader);
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
*/
|
||||
/** Creates a new DriveSubsystem. */
|
||||
public DriveSubsystem() {
|
||||
m_leftFollower.follow(m_leftLeader);
|
||||
m_rightFollower.follow(m_rightLeader);
|
||||
@@ -62,12 +60,14 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
* @param right The right wheel state.
|
||||
*/
|
||||
public void setDriveStates(TrapezoidProfile.State left, TrapezoidProfile.State right) {
|
||||
m_leftLeader.setSetpoint(ExampleSmartMotorController.PIDMode.kPosition,
|
||||
left.position,
|
||||
m_feedforward.calculate(left.velocity));
|
||||
m_rightLeader.setSetpoint(ExampleSmartMotorController.PIDMode.kPosition,
|
||||
right.position,
|
||||
m_feedforward.calculate(right.velocity));
|
||||
m_leftLeader.setSetpoint(
|
||||
ExampleSmartMotorController.PIDMode.kPosition,
|
||||
left.position,
|
||||
m_feedforward.calculate(left.velocity));
|
||||
m_rightLeader.setSetpoint(
|
||||
ExampleSmartMotorController.PIDMode.kPosition,
|
||||
right.position,
|
||||
m_feedforward.calculate(right.velocity));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -88,16 +88,14 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
return m_rightLeader.getEncoderDistance();
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the drive encoders.
|
||||
*/
|
||||
/** Resets the drive encoders. */
|
||||
public void resetEncoders() {
|
||||
m_leftLeader.resetEncoder();
|
||||
m_rightLeader.resetEncoder();
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
* @param maxOutput the maximum output to which the drive will be constrained
|
||||
*/
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.dutycycleencoder;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -39,5 +39,4 @@ public class Robot extends TimedRobot {
|
||||
SmartDashboard.putNumber("Output", output);
|
||||
SmartDashboard.putNumber("Distance", distance);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.dutycycleinput;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -32,5 +32,4 @@ public class Robot extends TimedRobot {
|
||||
SmartDashboard.putNumber("Frequency", frequency);
|
||||
SmartDashboard.putNumber("Duty Cycle", output);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.elevatorprofiledpid;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.elevatorsimulation;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -10,17 +10,15 @@ import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.RobotController;
|
||||
import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj.simulation.BatterySim;
|
||||
import edu.wpi.first.wpilibj.simulation.ElevatorSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.simulation.RoboRioSim;
|
||||
import edu.wpi.first.wpilibj.system.plant.DCMotor;
|
||||
import edu.wpi.first.wpilibj.util.Units;
|
||||
import edu.wpi.first.wpiutil.math.VecBuilder;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate the use of elevator simulation with existing code.
|
||||
*/
|
||||
/** This is a sample program to demonstrate the use of elevator simulation with existing code. */
|
||||
public class Robot extends TimedRobot {
|
||||
private static final int kMotorPort = 0;
|
||||
private static final int kEncoderAChannel = 0;
|
||||
@@ -37,7 +35,8 @@ public class Robot extends TimedRobot {
|
||||
|
||||
// distance per pulse = (distance per revolution) / (pulses per revolution)
|
||||
// = (Pi * D) / ppr
|
||||
private static final double kElevatorEncoderDistPerPulse = 2.0 * Math.PI * kElevatorDrumRadius / 4096;
|
||||
private static final double kElevatorEncoderDistPerPulse =
|
||||
2.0 * Math.PI * kElevatorDrumRadius / 4096;
|
||||
|
||||
private final DCMotor m_elevatorGearbox = DCMotor.getVex775Pro(4);
|
||||
|
||||
@@ -48,13 +47,15 @@ public class Robot extends TimedRobot {
|
||||
private final Joystick m_joystick = new Joystick(kJoystickPort);
|
||||
|
||||
// Simulation classes help us simulate what's going on, including gravity.
|
||||
private final ElevatorSim m_elevatorSim = new ElevatorSim(m_elevatorGearbox,
|
||||
kElevatorGearing,
|
||||
kCarriageMass,
|
||||
kElevatorDrumRadius,
|
||||
kMinElevatorHeight,
|
||||
kMaxElevatorHeight,
|
||||
VecBuilder.fill(0.01));
|
||||
private final ElevatorSim m_elevatorSim =
|
||||
new ElevatorSim(
|
||||
m_elevatorGearbox,
|
||||
kElevatorGearing,
|
||||
kCarriageMass,
|
||||
kElevatorDrumRadius,
|
||||
kMinElevatorHeight,
|
||||
kMaxElevatorHeight,
|
||||
VecBuilder.fill(0.01));
|
||||
private final EncoderSim m_encoderSim = new EncoderSim(m_encoder);
|
||||
|
||||
@Override
|
||||
@@ -74,7 +75,8 @@ public class Robot extends TimedRobot {
|
||||
// Finally, we set our simulated encoder's readings and simulated battery voltage
|
||||
m_encoderSim.setDistance(m_elevatorSim.getPositionMeters());
|
||||
// SimBattery estimates loaded battery voltages
|
||||
RoboRioSim.setVInVoltage(BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDrawAmps()));
|
||||
RoboRioSim.setVInVoltage(
|
||||
BatterySim.calculateDefaultBatteryLoadedVoltage(m_elevatorSim.getCurrentDrawAmps()));
|
||||
}
|
||||
|
||||
@Override
|
||||
|
||||
@@ -24,8 +24,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param port The port for the controller.
|
||||
*/
|
||||
@SuppressWarnings("PMD.UnusedFormalParameter")
|
||||
public ExampleSmartMotorController(int port) {
|
||||
}
|
||||
public ExampleSmartMotorController(int port) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the PID gains of the smart controller.
|
||||
@@ -34,8 +33,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param ki The integral gain.
|
||||
* @param kd The derivative gain.
|
||||
*/
|
||||
public void setPID(double kp, double ki, double kd) {
|
||||
}
|
||||
public void setPID(double kp, double ki, double kd) {}
|
||||
|
||||
/**
|
||||
* Example method for setting the setpoint of the smart controller in PID mode.
|
||||
@@ -44,16 +42,14 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
* @param setpoint The controller setpoint.
|
||||
* @param arbFeedforward An arbitrary feedforward output (from -1 to 1).
|
||||
*/
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {
|
||||
}
|
||||
public void setSetpoint(PIDMode mode, double setpoint, double arbFeedforward) {}
|
||||
|
||||
/**
|
||||
* Places this motor controller in follower mode.
|
||||
*
|
||||
* @param leader The leader to follow.
|
||||
*/
|
||||
public void follow(ExampleSmartMotorController leader) {
|
||||
}
|
||||
public void follow(ExampleSmartMotorController leader) {}
|
||||
|
||||
/**
|
||||
* Returns the encoder distance.
|
||||
@@ -73,15 +69,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
return 0;
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the encoder to zero distance.
|
||||
*/
|
||||
public void resetEncoder() {
|
||||
}
|
||||
/** Resets the encoder to zero distance. */
|
||||
public void resetEncoder() {}
|
||||
|
||||
@Override
|
||||
public void set(double speed) {
|
||||
}
|
||||
public void set(double speed) {}
|
||||
|
||||
@Override
|
||||
public double get() {
|
||||
@@ -89,9 +81,7 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void setInverted(boolean isInverted) {
|
||||
|
||||
}
|
||||
public void setInverted(boolean isInverted) {}
|
||||
|
||||
@Override
|
||||
public boolean getInverted() {
|
||||
@@ -99,14 +89,11 @@ public class ExampleSmartMotorController implements SpeedController {
|
||||
}
|
||||
|
||||
@Override
|
||||
public void disable() {
|
||||
}
|
||||
public void disable() {}
|
||||
|
||||
@Override
|
||||
public void stopMotor() {
|
||||
}
|
||||
public void stopMotor() {}
|
||||
|
||||
@Override
|
||||
public void pidWrite(double output) {
|
||||
}
|
||||
public void pidWrite(double output) {}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.elevatortrapezoidprofile;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -46,7 +46,9 @@ public class Robot extends TimedRobot {
|
||||
m_setpoint = profile.calculate(kDt);
|
||||
|
||||
// Send setpoint to offboard controller PID
|
||||
m_motor.setSetpoint(ExampleSmartMotorController.PIDMode.kPosition, m_setpoint.position,
|
||||
m_feedforward.calculate(m_setpoint.velocity) / 12.0);
|
||||
m_motor.setSetpoint(
|
||||
ExampleSmartMotorController.PIDMode.kPosition,
|
||||
m_setpoint.position,
|
||||
m_feedforward.calculate(m_setpoint.velocity) / 12.0);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.encoder;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -26,14 +26,13 @@ public class Robot extends TimedRobot {
|
||||
* The Encoder object is constructed with 4 parameters, the last two being optional. The first two
|
||||
* parameters (1, 2 in this case) refer to the ports on the roboRIO which the encoder uses.
|
||||
* Because a quadrature encoder has two signal wires, the signal from two DIO ports on the roboRIO
|
||||
* are used. The third (optional) parameter is a boolean which defaults to false. If you set this
|
||||
* parameter to true, the direction of the encoder will be reversed, in case it makes more sense
|
||||
* are used. The third (optional) parameter is a boolean which defaults to false. If you set this
|
||||
* parameter to true, the direction of the encoder will be reversed, in case it makes more sense
|
||||
* mechanically. The final (optional) parameter specifies encoding rate (k1X, k2X, or k4X) and
|
||||
* defaults to k4X. Faster (k4X) encoding gives greater positional precision but more noise in the
|
||||
* rate.
|
||||
*/
|
||||
private final Encoder m_encoder =
|
||||
new Encoder(1, 2, false, CounterBase.EncodingType.k4X);
|
||||
private final Encoder m_encoder = new Encoder(1, 2, false, CounterBase.EncodingType.k4X);
|
||||
|
||||
@Override
|
||||
public void robotInit() {
|
||||
|
||||
@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.frisbeebot;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be
|
||||
* declared globally (i.e. public static). Do not put anything functional in this class.
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
@@ -19,8 +19,8 @@ public final class Constants {
|
||||
public static final int kRightMotor1Port = 2;
|
||||
public static final int kRightMotor2Port = 3;
|
||||
|
||||
public static final int[] kLeftEncoderPorts = new int[]{0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[]{2, 3};
|
||||
public static final int[] kLeftEncoderPorts = new int[] {0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[] {2, 3};
|
||||
public static final boolean kLeftEncoderReversed = false;
|
||||
public static final boolean kRightEncoderReversed = true;
|
||||
|
||||
@@ -32,7 +32,7 @@ public final class Constants {
|
||||
}
|
||||
|
||||
public static final class ShooterConstants {
|
||||
public static final int[] kEncoderPorts = new int[]{4, 5};
|
||||
public static final int[] kEncoderPorts = new int[] {4, 5};
|
||||
public static final boolean kEncoderReversed = false;
|
||||
public static final int kEncoderCPR = 1024;
|
||||
public static final double kEncoderDistancePerPulse =
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,20 +46,14 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -77,12 +71,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -95,13 +86,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -109,10 +96,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -4,8 +4,14 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.frisbeebot;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.AutoConstants;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.ShooterSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.ConditionalCommand;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
@@ -14,18 +20,11 @@ import edu.wpi.first.wpilibj2.command.WaitCommand;
|
||||
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.AutoConstants;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.OIConstants;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.ShooterSubsystem;
|
||||
|
||||
import static edu.wpi.first.wpilibj.XboxController.Button;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||
* (including subsystems, commands, and button mappings) should be declared here.
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The robot's subsystems
|
||||
@@ -35,28 +34,28 @@ public class RobotContainer {
|
||||
// A simple autonomous routine that shoots the loaded frisbees
|
||||
private final Command m_autoCommand =
|
||||
// Start the command by spinning up the shooter...
|
||||
new InstantCommand(m_shooter::enable, m_shooter).andThen(
|
||||
// Wait until the shooter is at speed before feeding the frisbees
|
||||
new WaitUntilCommand(m_shooter::atSetpoint),
|
||||
// Start running the feeder
|
||||
new InstantCommand(m_shooter::runFeeder, m_shooter),
|
||||
// Shoot for the specified time
|
||||
new WaitCommand(AutoConstants.kAutoShootTimeSeconds))
|
||||
new InstantCommand(m_shooter::enable, m_shooter)
|
||||
.andThen(
|
||||
// Wait until the shooter is at speed before feeding the frisbees
|
||||
new WaitUntilCommand(m_shooter::atSetpoint),
|
||||
// Start running the feeder
|
||||
new InstantCommand(m_shooter::runFeeder, m_shooter),
|
||||
// Shoot for the specified time
|
||||
new WaitCommand(AutoConstants.kAutoShootTimeSeconds))
|
||||
// Add a timeout (will end the command if, for instance, the shooter never gets up to
|
||||
// speed)
|
||||
.withTimeout(AutoConstants.kAutoTimeoutSeconds)
|
||||
// When the command ends, turn off the shooter and the feeder
|
||||
.andThen(() -> {
|
||||
m_shooter.disable();
|
||||
m_shooter.stopFeeder();
|
||||
});
|
||||
.andThen(
|
||||
() -> {
|
||||
m_shooter.disable();
|
||||
m_shooter.stopFeeder();
|
||||
});
|
||||
|
||||
// The driver's controller
|
||||
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
*/
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Configure the button bindings
|
||||
configureButtonBindings();
|
||||
@@ -66,17 +65,19 @@ public class RobotContainer {
|
||||
m_robotDrive.setDefaultCommand(
|
||||
// A split-stick arcade command, with forward/backward controlled by the left
|
||||
// hand, and turning controlled by the right.
|
||||
new RunCommand(() -> m_robotDrive
|
||||
.arcadeDrive(m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)), m_robotDrive));
|
||||
|
||||
new RunCommand(
|
||||
() ->
|
||||
m_robotDrive.arcadeDrive(
|
||||
m_driverController.getY(GenericHID.Hand.kLeft),
|
||||
m_driverController.getX(GenericHID.Hand.kRight)),
|
||||
m_robotDrive));
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a
|
||||
* {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}.
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
// Spin up the shooter when the 'A' button is pressed
|
||||
@@ -88,14 +89,17 @@ public class RobotContainer {
|
||||
.whenPressed(new InstantCommand(m_shooter::disable, m_shooter));
|
||||
|
||||
// Run the feeder when the 'X' button is held, but only if the shooter is at speed
|
||||
new JoystickButton(m_driverController, Button.kX.value).whenPressed(new ConditionalCommand(
|
||||
// Run the feeder
|
||||
new InstantCommand(m_shooter::runFeeder, m_shooter),
|
||||
// Do nothing
|
||||
new InstantCommand(),
|
||||
// Determine which of the above to do based on whether the shooter has reached the
|
||||
// desired speed
|
||||
m_shooter::atSetpoint)).whenReleased(new InstantCommand(m_shooter::stopFeeder, m_shooter));
|
||||
new JoystickButton(m_driverController, Button.kX.value)
|
||||
.whenPressed(
|
||||
new ConditionalCommand(
|
||||
// Run the feeder
|
||||
new InstantCommand(m_shooter::runFeeder, m_shooter),
|
||||
// Do nothing
|
||||
new InstantCommand(),
|
||||
// Determine which of the above to do based on whether the shooter has reached the
|
||||
// desired speed
|
||||
m_shooter::atSetpoint))
|
||||
.whenReleased(new InstantCommand(m_shooter::stopFeeder, m_shooter));
|
||||
|
||||
// Drive at half speed when the bumper is held
|
||||
new JoystickButton(m_driverController, Button.kBumperRight.value)
|
||||
@@ -103,7 +107,6 @@ public class RobotContainer {
|
||||
.whenReleased(() -> m_robotDrive.setMaxOutput(1));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||
*
|
||||
|
||||
@@ -8,37 +8,40 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
// The motors on the left side of the drive.
|
||||
private final SpeedControllerGroup m_leftMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kLeftMotor2Port));
|
||||
|
||||
// The motors on the right side of the drive.
|
||||
private final SpeedControllerGroup m_rightMotors =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
new SpeedControllerGroup(
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor1Port),
|
||||
new PWMVictorSPX(DriveConstants.kRightMotor2Port));
|
||||
|
||||
// The robot's drive
|
||||
private final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotors, m_rightMotors);
|
||||
|
||||
// The left-side drive encoder
|
||||
private final Encoder m_leftEncoder =
|
||||
new Encoder(DriveConstants.kLeftEncoderPorts[0], DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kLeftEncoderPorts[0],
|
||||
DriveConstants.kLeftEncoderPorts[1],
|
||||
DriveConstants.kLeftEncoderReversed);
|
||||
|
||||
// The right-side drive encoder
|
||||
private final Encoder m_rightEncoder =
|
||||
new Encoder(DriveConstants.kRightEncoderPorts[0], DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
new Encoder(
|
||||
DriveConstants.kRightEncoderPorts[0],
|
||||
DriveConstants.kRightEncoderPorts[1],
|
||||
DriveConstants.kRightEncoderReversed);
|
||||
|
||||
/**
|
||||
* Creates a new DriveSubsystem.
|
||||
*/
|
||||
/** Creates a new DriveSubsystem. */
|
||||
public DriveSubsystem() {
|
||||
// Sets the distance per pulse for the encoders
|
||||
m_leftEncoder.setDistancePerPulse(DriveConstants.kEncoderDistancePerPulse);
|
||||
@@ -55,9 +58,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
m_drive.arcadeDrive(fwd, rot);
|
||||
}
|
||||
|
||||
/**
|
||||
* Resets the drive encoders to currently read a position of 0.
|
||||
*/
|
||||
/** Resets the drive encoders to currently read a position of 0. */
|
||||
public void resetEncoders() {
|
||||
m_leftEncoder.reset();
|
||||
m_rightEncoder.reset();
|
||||
@@ -91,7 +92,7 @@ public class DriveSubsystem extends SubsystemBase {
|
||||
}
|
||||
|
||||
/**
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
* Sets the max output of the drive. Useful for scaling the drive to drive more slowly.
|
||||
*
|
||||
* @param maxOutput the maximum output to which the drive will be constrained
|
||||
*/
|
||||
|
||||
@@ -8,23 +8,22 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.controller.SimpleMotorFeedforward;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
public class ShooterSubsystem extends PIDSubsystem {
|
||||
private final PWMVictorSPX m_shooterMotor = new PWMVictorSPX(ShooterConstants.kShooterMotorPort);
|
||||
private final PWMVictorSPX m_feederMotor = new PWMVictorSPX(ShooterConstants.kFeederMotorPort);
|
||||
private final Encoder m_shooterEncoder =
|
||||
new Encoder(ShooterConstants.kEncoderPorts[0], ShooterConstants.kEncoderPorts[1],
|
||||
ShooterConstants.kEncoderReversed);
|
||||
new Encoder(
|
||||
ShooterConstants.kEncoderPorts[0],
|
||||
ShooterConstants.kEncoderPorts[1],
|
||||
ShooterConstants.kEncoderReversed);
|
||||
private final SimpleMotorFeedforward m_shooterFeedforward =
|
||||
new SimpleMotorFeedforward(ShooterConstants.kSVolts,
|
||||
ShooterConstants.kVVoltSecondsPerRotation);
|
||||
new SimpleMotorFeedforward(
|
||||
ShooterConstants.kSVolts, ShooterConstants.kVVoltSecondsPerRotation);
|
||||
|
||||
/**
|
||||
* The shooter subsystem for the robot.
|
||||
*/
|
||||
/** The shooter subsystem for the robot. */
|
||||
public ShooterSubsystem() {
|
||||
super(new PIDController(ShooterConstants.kP, ShooterConstants.kI, ShooterConstants.kD));
|
||||
getController().setTolerance(ShooterConstants.kShooterToleranceRPS);
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,20 +46,14 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -70,12 +64,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -88,12 +79,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -101,10 +89,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -8,11 +8,6 @@ import edu.wpi.first.wpilibj.GenericHID;
|
||||
import edu.wpi.first.wpilibj.GenericHID.Hand;
|
||||
import edu.wpi.first.wpilibj.Joystick;
|
||||
import edu.wpi.first.wpilibj.XboxController;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.commands.Autonomous;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.commands.CloseClaw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.commands.OpenClaw;
|
||||
@@ -26,12 +21,16 @@ import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
/**
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* This class is where the bulk of the robot should be declared. Since Command-based is a
|
||||
* "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot
|
||||
* (including subsystems, commands, and button mappings) should be declared here.
|
||||
* periodic methods (other than the scheduler calls). Instead, the structure of the robot (including
|
||||
* subsystems, commands, and button mappings) should be declared here.
|
||||
*/
|
||||
public class RobotContainer {
|
||||
// The robot's subsystems and commands are defined here...
|
||||
@@ -45,9 +44,7 @@ public class RobotContainer {
|
||||
private final CommandBase m_autonomousCommand =
|
||||
new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator);
|
||||
|
||||
/**
|
||||
* The container for the robot. Contains subsystems, OI devices, and commands.
|
||||
*/
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
public RobotContainer() {
|
||||
// Put Some buttons on the SmartDashboard
|
||||
SmartDashboard.putData("Elevator Bottom", new SetElevatorSetpoint(0, m_elevator));
|
||||
@@ -60,12 +57,13 @@ public class RobotContainer {
|
||||
SmartDashboard.putData("Open Claw", new OpenClaw(m_claw));
|
||||
SmartDashboard.putData("Close Claw", new CloseClaw(m_claw));
|
||||
|
||||
SmartDashboard
|
||||
.putData("Deliver Soda", new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
|
||||
SmartDashboard.putData(
|
||||
"Deliver Soda", new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
|
||||
|
||||
// Assign default commands
|
||||
m_drivetrain.setDefaultCommand(new TankDrive(() -> m_joystick.getY(Hand.kLeft),
|
||||
() -> m_joystick.getY(Hand.kRight), m_drivetrain));
|
||||
m_drivetrain.setDefaultCommand(
|
||||
new TankDrive(
|
||||
() -> m_joystick.getY(Hand.kLeft), () -> m_joystick.getY(Hand.kRight), m_drivetrain));
|
||||
|
||||
// Show what command your subsystem is running on the SmartDashboard
|
||||
SmartDashboard.putData(m_drivetrain);
|
||||
@@ -78,10 +76,10 @@ public class RobotContainer {
|
||||
}
|
||||
|
||||
/**
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* Use this method to define your button->command mappings. Buttons can be created by
|
||||
* instantiating a {@link GenericHID} or one of its subclasses ({@link
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a
|
||||
* {@link edu.wpi.first.wpilibj2.command.button.JoystickButton}.
|
||||
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
|
||||
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
|
||||
*/
|
||||
private void configureButtonBindings() {
|
||||
// Create some buttons
|
||||
@@ -106,7 +104,6 @@ public class RobotContainer {
|
||||
l2.whenPressed(new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator));
|
||||
}
|
||||
|
||||
|
||||
/**
|
||||
* Use this to pass the autonomous command to the main {@link Robot} class.
|
||||
*
|
||||
|
||||
@@ -4,20 +4,15 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
/**
|
||||
* The main autonomous command to pickup and deliver the soda to the box.
|
||||
*/
|
||||
/** The main autonomous command to pickup and deliver the soda to the box. */
|
||||
public class Autonomous extends SequentialCommandGroup {
|
||||
/**
|
||||
* Create a new autonomous command.
|
||||
*/
|
||||
/** Create a new autonomous command. */
|
||||
public Autonomous(DriveTrain drive, Claw claw, Wrist wrist, Elevator elevator) {
|
||||
addCommands(
|
||||
new PrepareToPickup(claw, wrist, elevator),
|
||||
@@ -27,10 +22,6 @@ public class Autonomous extends SequentialCommandGroup {
|
||||
new Place(claw, wrist, elevator),
|
||||
new SetDistanceToBox(0.60, drive),
|
||||
// new DriveStraight(-2), // Use Encoders if ultrasonic is broken
|
||||
parallel(
|
||||
new SetWristSetpoint(-45, wrist),
|
||||
new CloseClaw(claw)
|
||||
)
|
||||
);
|
||||
parallel(new SetWristSetpoint(-45, wrist), new CloseClaw(claw)));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,14 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
/**
|
||||
* Closes the claw until the limit switch is tripped.
|
||||
*/
|
||||
/** Closes the claw until the limit switch is tripped. */
|
||||
public class CloseClaw extends CommandBase {
|
||||
private final Claw m_claw;
|
||||
|
||||
|
||||
@@ -5,28 +5,25 @@
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
import edu.wpi.first.wpilibj2.command.PIDCommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
|
||||
/**
|
||||
* Drive the given distance straight (negative values go backwards). Uses a
|
||||
* local PID controller to run a simple PID loop that is only enabled while this
|
||||
* command is running. The input is the averaged values of the left and right
|
||||
* encoders.
|
||||
* Drive the given distance straight (negative values go backwards). Uses a local PID controller to
|
||||
* run a simple PID loop that is only enabled while this command is running. The input is the
|
||||
* averaged values of the left and right encoders.
|
||||
*/
|
||||
public class DriveStraight extends PIDCommand {
|
||||
private final DriveTrain m_drivetrain;
|
||||
|
||||
/**
|
||||
* Create a new DriveStraight command.
|
||||
*
|
||||
* @param distance The distance to drive
|
||||
*/
|
||||
public DriveStraight(double distance, DriveTrain drivetrain) {
|
||||
super(new PIDController(4, 0, 0),
|
||||
drivetrain::getDistance,
|
||||
distance,
|
||||
d -> drivetrain.drive(d, d));
|
||||
super(
|
||||
new PIDController(4, 0, 0), drivetrain::getDistance, distance, d -> drivetrain.drive(d, d));
|
||||
|
||||
m_drivetrain = drivetrain;
|
||||
addRequirements(m_drivetrain);
|
||||
|
||||
@@ -4,13 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj2.command.WaitCommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
|
||||
/**
|
||||
* Opens the claw for one second. Real robots should use sensors, stalling motors is BAD!
|
||||
*/
|
||||
/** Opens the claw for one second. Real robots should use sensors, stalling motors is BAD! */
|
||||
public class OpenClaw extends WaitCommand {
|
||||
private final Claw m_claw;
|
||||
|
||||
|
||||
@@ -4,12 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
/**
|
||||
* Pickup a soda can (if one is between the open claws) and get it in a safe state to drive around.
|
||||
@@ -18,15 +16,13 @@ public class Pickup extends SequentialCommandGroup {
|
||||
/**
|
||||
* Create a new pickup command.
|
||||
*
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param elevator The elevator subsystem to use
|
||||
*/
|
||||
public Pickup(Claw claw, Wrist wrist, Elevator elevator) {
|
||||
addCommands(
|
||||
new CloseClaw(claw),
|
||||
parallel(
|
||||
new SetWristSetpoint(-45, wrist),
|
||||
new SetElevatorSetpoint(0.25, elevator)));
|
||||
parallel(new SetWristSetpoint(-45, wrist), new SetElevatorSetpoint(0.25, elevator)));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -4,22 +4,18 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
/**
|
||||
* Place a held soda can onto the platform.
|
||||
*/
|
||||
/** Place a held soda can onto the platform. */
|
||||
public class Place extends SequentialCommandGroup {
|
||||
/**
|
||||
* Create a new place command.
|
||||
*
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param elevator The elevator subsystem to use
|
||||
*/
|
||||
public Place(Claw claw, Wrist wrist, Elevator elevator) {
|
||||
|
||||
@@ -4,28 +4,23 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
|
||||
|
||||
/**
|
||||
* Make sure the robot is in a state to pickup soda cans.
|
||||
*/
|
||||
/** Make sure the robot is in a state to pickup soda cans. */
|
||||
public class PrepareToPickup extends SequentialCommandGroup {
|
||||
/**
|
||||
* Create a new prepare to pickup command.
|
||||
*
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param claw The claw subsystem to use
|
||||
* @param wrist The wrist subsystem to use
|
||||
* @param elevator The elevator subsystem to use
|
||||
*/
|
||||
public PrepareToPickup(Claw claw, Wrist wrist, Elevator elevator) {
|
||||
addCommands(
|
||||
new OpenClaw(claw),
|
||||
parallel(
|
||||
new SetWristSetpoint(0, wrist),
|
||||
new SetElevatorSetpoint(0, elevator)));
|
||||
parallel(new SetWristSetpoint(0, wrist), new SetElevatorSetpoint(0, elevator)));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,16 +5,13 @@
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
import edu.wpi.first.wpilibj2.command.PIDCommand;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
|
||||
|
||||
/**
|
||||
* Drive until the robot is the given distance away from the box. Uses a local
|
||||
* PID controller to run a simple PID loop that is only enabled while this
|
||||
* command is running. The input is the averaged values of the left and right
|
||||
* encoders.
|
||||
* Drive until the robot is the given distance away from the box. Uses a local PID controller to run
|
||||
* a simple PID loop that is only enabled while this command is running. The input is the averaged
|
||||
* values of the left and right encoders.
|
||||
*/
|
||||
public class SetDistanceToBox extends PIDCommand {
|
||||
private final DriveTrain m_drivetrain;
|
||||
@@ -25,8 +22,10 @@ public class SetDistanceToBox extends PIDCommand {
|
||||
* @param distance The distance away from the box to drive to
|
||||
*/
|
||||
public SetDistanceToBox(double distance, DriveTrain drivetrain) {
|
||||
super(new PIDController(-2, 0, 0),
|
||||
drivetrain::getDistanceToObstacle, distance,
|
||||
super(
|
||||
new PIDController(-2, 0, 0),
|
||||
drivetrain::getDistanceToObstacle,
|
||||
distance,
|
||||
d -> drivetrain.drive(d, d));
|
||||
|
||||
m_drivetrain = drivetrain;
|
||||
|
||||
@@ -4,10 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
/**
|
||||
* Move the elevator to a given location. This command finishes when it is within the tolerance, but
|
||||
|
||||
@@ -4,10 +4,8 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
/**
|
||||
* Move the wrist to a given angle. This command finishes when it is within the tolerance, but
|
||||
@@ -22,7 +20,7 @@ public class SetWristSetpoint extends CommandBase {
|
||||
* Create a new SetWristSetpoint command.
|
||||
*
|
||||
* @param setpoint The setpoint to set the wrist to
|
||||
* @param wrist The wrist to use
|
||||
* @param wrist The wrist to use
|
||||
*/
|
||||
public SetWristSetpoint(double setpoint, Wrist wrist) {
|
||||
m_wrist = wrist;
|
||||
|
||||
@@ -4,16 +4,11 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
|
||||
|
||||
/**
|
||||
* Have the robot drive tank style.
|
||||
*/
|
||||
/** Have the robot drive tank style. */
|
||||
public class TankDrive extends CommandBase {
|
||||
private final DriveTrain m_drivetrain;
|
||||
private final DoubleSupplier m_left;
|
||||
@@ -22,8 +17,8 @@ public class TankDrive extends CommandBase {
|
||||
/**
|
||||
* Creates a new TankDrive command.
|
||||
*
|
||||
* @param left The control input for the left side of the drive
|
||||
* @param right The control input for the right sight of the drive
|
||||
* @param left The control input for the left side of the drive
|
||||
* @param right The control input for the right sight of the drive
|
||||
* @param drivetrain The drivetrain subsystem to drive
|
||||
*/
|
||||
public TankDrive(DoubleSupplier left, DoubleSupplier right, DriveTrain drivetrain) {
|
||||
|
||||
@@ -17,9 +17,7 @@ public class Claw extends SubsystemBase {
|
||||
private final Victor m_motor = new Victor(7);
|
||||
private final DigitalInput m_contact = new DigitalInput(5);
|
||||
|
||||
/**
|
||||
* Create a new claw subsystem.
|
||||
*/
|
||||
/** Create a new claw subsystem. */
|
||||
public Claw() {
|
||||
// Let's name everything on the LiveWindow
|
||||
addChild("Motor", m_motor);
|
||||
@@ -30,37 +28,27 @@ public class Claw extends SubsystemBase {
|
||||
SmartDashboard.putData("Claw switch", m_contact);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the claw motor to move in the open direction.
|
||||
*/
|
||||
/** Set the claw motor to move in the open direction. */
|
||||
public void open() {
|
||||
m_motor.set(-1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the claw motor to move in the close direction.
|
||||
*/
|
||||
/** Set the claw motor to move in the close direction. */
|
||||
public void close() {
|
||||
m_motor.set(1);
|
||||
}
|
||||
|
||||
/**
|
||||
* Stops the claw motor from moving.
|
||||
*/
|
||||
/** Stops the claw motor from moving. */
|
||||
public void stop() {
|
||||
m_motor.set(0);
|
||||
}
|
||||
|
||||
/**
|
||||
* Return true when the robot is grabbing an object hard enough to trigger the limit switch.
|
||||
*/
|
||||
/** Return true when the robot is grabbing an object hard enough to trigger the limit switch. */
|
||||
public boolean isGrabbing() {
|
||||
return m_contact.get();
|
||||
}
|
||||
|
||||
/**
|
||||
* Call log method every loop.
|
||||
*/
|
||||
/** Call log method every loop. */
|
||||
@Override
|
||||
public void periodic() {
|
||||
log();
|
||||
|
||||
@@ -11,11 +11,10 @@ import edu.wpi.first.wpilibj.PWMVictorSPX;
|
||||
import edu.wpi.first.wpilibj.SpeedController;
|
||||
import edu.wpi.first.wpilibj.SpeedControllerGroup;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
|
||||
public class DriveTrain extends SubsystemBase {
|
||||
/**
|
||||
* The DriveTrain subsystem incorporates the sensors and actuators attached to the robots chassis.
|
||||
@@ -23,6 +22,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
*/
|
||||
private final SpeedController m_leftMotor =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(0), new PWMVictorSPX(1));
|
||||
|
||||
private final SpeedController m_rightMotor =
|
||||
new SpeedControllerGroup(new PWMVictorSPX(2), new PWMVictorSPX(3));
|
||||
|
||||
@@ -33,9 +33,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
private final AnalogInput m_rangefinder = new AnalogInput(6);
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(1);
|
||||
|
||||
/**
|
||||
* Create a new drive train subsystem.
|
||||
*/
|
||||
/** Create a new drive train subsystem. */
|
||||
public DriveTrain() {
|
||||
super();
|
||||
|
||||
@@ -61,9 +59,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
addChild("Gyro", m_gyro);
|
||||
}
|
||||
|
||||
/**
|
||||
* The log method puts interesting information to the SmartDashboard.
|
||||
*/
|
||||
/** The log method puts interesting information to the SmartDashboard. */
|
||||
public void log() {
|
||||
SmartDashboard.putNumber("Left Distance", m_leftEncoder.getDistance());
|
||||
SmartDashboard.putNumber("Right Distance", m_rightEncoder.getDistance());
|
||||
@@ -75,7 +71,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
/**
|
||||
* Tank style driving for the DriveTrain.
|
||||
*
|
||||
* @param left Speed in range [-1,1]
|
||||
* @param left Speed in range [-1,1]
|
||||
* @param right Speed in range [-1,1]
|
||||
*/
|
||||
public void drive(double left, double right) {
|
||||
@@ -91,9 +87,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
return m_gyro.getAngle();
|
||||
}
|
||||
|
||||
/**
|
||||
* Reset the robots sensors to the zero states.
|
||||
*/
|
||||
/** Reset the robots sensors to the zero states. */
|
||||
public void reset() {
|
||||
m_gyro.reset();
|
||||
m_leftEncoder.reset();
|
||||
@@ -119,9 +113,7 @@ public class DriveTrain extends SubsystemBase {
|
||||
return m_rangefinder.getAverageVoltage();
|
||||
}
|
||||
|
||||
/**
|
||||
* Call log method every loop.
|
||||
*/
|
||||
/** Call log method every loop. */
|
||||
@Override
|
||||
public void periodic() {
|
||||
log();
|
||||
|
||||
@@ -7,11 +7,10 @@ package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
|
||||
import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.Victor;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
|
||||
/**
|
||||
* The elevator subsystem uses PID to go to a given height. Unfortunately, in it's current state PID
|
||||
* values for simulation are different than in the real world do to minor differences.
|
||||
@@ -25,9 +24,7 @@ public class Elevator extends PIDSubsystem {
|
||||
private static final double kP_simulation = 18;
|
||||
private static final double kI_simulation = 0.2;
|
||||
|
||||
/**
|
||||
* Create a new elevator subsystem.
|
||||
*/
|
||||
/** Create a new elevator subsystem. */
|
||||
public Elevator() {
|
||||
super(new PIDController(kP_real, kI_real, 0));
|
||||
if (Robot.isSimulation()) { // Check for simulation and update PID values
|
||||
@@ -50,9 +47,7 @@ public class Elevator extends PIDSubsystem {
|
||||
addChild("Pot", m_pot);
|
||||
}
|
||||
|
||||
/**
|
||||
* The log method puts interesting information to the SmartDashboard.
|
||||
*/
|
||||
/** The log method puts interesting information to the SmartDashboard. */
|
||||
public void log() {
|
||||
SmartDashboard.putData("Elevator Pot", m_pot);
|
||||
}
|
||||
@@ -65,17 +60,13 @@ public class Elevator extends PIDSubsystem {
|
||||
return m_pot.get();
|
||||
}
|
||||
|
||||
/**
|
||||
* Use the motor as the PID output. This method is automatically called by the subsystem.
|
||||
*/
|
||||
/** Use the motor as the PID output. This method is automatically called by the subsystem. */
|
||||
@Override
|
||||
public void useOutput(double output, double setpoint) {
|
||||
m_motor.set(output);
|
||||
}
|
||||
|
||||
/**
|
||||
* Call log method every loop.
|
||||
*/
|
||||
/** Call log method every loop. */
|
||||
@Override
|
||||
public void periodic() {
|
||||
log();
|
||||
|
||||
@@ -7,11 +7,10 @@ package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
|
||||
import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.Victor;
|
||||
import edu.wpi.first.wpilibj.controller.PIDController;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.PIDSubsystem;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
|
||||
/**
|
||||
* The wrist subsystem is like the elevator, but with a rotational joint instead of a linear joint.
|
||||
*/
|
||||
@@ -22,9 +21,7 @@ public class Wrist extends PIDSubsystem {
|
||||
private static final double kP_real = 1;
|
||||
private static final double kP_simulation = 0.05;
|
||||
|
||||
/**
|
||||
* Create a new wrist subsystem.
|
||||
*/
|
||||
/** Create a new wrist subsystem. */
|
||||
public Wrist() {
|
||||
super(new PIDController(kP_real, 0, 0));
|
||||
if (Robot.isSimulation()) { // Check for simulation and update PID values
|
||||
@@ -47,9 +44,7 @@ public class Wrist extends PIDSubsystem {
|
||||
addChild("Pot", m_pot);
|
||||
}
|
||||
|
||||
/**
|
||||
* The log method puts interesting information to the SmartDashboard.
|
||||
*/
|
||||
/** The log method puts interesting information to the SmartDashboard. */
|
||||
public void log() {
|
||||
SmartDashboard.putData("Wrist Angle", m_pot);
|
||||
}
|
||||
@@ -62,17 +57,13 @@ public class Wrist extends PIDSubsystem {
|
||||
return m_pot.get();
|
||||
}
|
||||
|
||||
/**
|
||||
* Use the motor as the PID output. This method is automatically called by the subsystem.
|
||||
*/
|
||||
/** Use the motor as the PID output. This method is automatically called by the subsystem. */
|
||||
@Override
|
||||
public void useOutput(double output, double setpoint) {
|
||||
m_motor.set(output);
|
||||
}
|
||||
|
||||
/**
|
||||
* Call log method every loop.
|
||||
*/
|
||||
/** Call log method every loop. */
|
||||
@Override
|
||||
public void periodic() {
|
||||
log();
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.gettingstarted;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -11,38 +11,32 @@ import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
|
||||
/**
|
||||
* The VM is configured to automatically run this class, and to call the
|
||||
* functions corresponding to each mode, as described in the TimedRobot
|
||||
* documentation. If you change the name of this class or the package after
|
||||
* creating this project, you must also update the manifest file in the resource
|
||||
* The VM is configured to automatically run this class, and to call the functions corresponding to
|
||||
* each mode, as described in the TimedRobot documentation. If you change the name of this class or
|
||||
* the package after creating this project, you must also update the manifest file in the resource
|
||||
* directory.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private final DifferentialDrive m_robotDrive
|
||||
= new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
|
||||
private final DifferentialDrive m_robotDrive =
|
||||
new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
|
||||
private final Joystick m_stick = new Joystick(0);
|
||||
private final Timer m_timer = new Timer();
|
||||
|
||||
/**
|
||||
* This function is run when the robot is first started up and should be
|
||||
* used for any initialization code.
|
||||
* This function is run when the robot is first started up and should be used for any
|
||||
* initialization code.
|
||||
*/
|
||||
@Override
|
||||
public void robotInit() {
|
||||
}
|
||||
public void robotInit() {}
|
||||
|
||||
/**
|
||||
* This function is run once each time the robot enters autonomous mode.
|
||||
*/
|
||||
/** This function is run once each time the robot enters autonomous mode. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_timer.reset();
|
||||
m_timer.start();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
// Drive for 2 seconds
|
||||
@@ -53,25 +47,17 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters teleoperated mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters teleoperated mode. */
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
}
|
||||
public void teleopInit() {}
|
||||
|
||||
/**
|
||||
* This function is called periodically during teleoperated mode.
|
||||
*/
|
||||
/** This function is called periodically during teleoperated mode. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
@@ -7,13 +7,12 @@ package edu.wpi.first.wpilibj.examples.gyro;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/**
|
||||
* Do NOT add any static variables to this class, or any initialization at all.
|
||||
* Unless you know what you are doing, do not modify this file except to
|
||||
* change the parameter class to the startRobot call.
|
||||
* Do NOT add any static variables to this class, or any initialization at all. Unless you know what
|
||||
* you are doing, do not modify this file except to change the parameter class to the startRobot
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -11,9 +11,9 @@ import edu.wpi.first.wpilibj.TimedRobot;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
|
||||
/**
|
||||
* This is a sample program to demonstrate how to use a gyro sensor to make a
|
||||
* robot drive straight. This program uses a joystick to drive forwards and
|
||||
* backwards while the gyro is used for direction keeping.
|
||||
* This is a sample program to demonstrate how to use a gyro sensor to make a robot drive straight.
|
||||
* This program uses a joystick to drive forwards and backwards while the gyro is used for direction
|
||||
* keeping.
|
||||
*/
|
||||
public class Robot extends TimedRobot {
|
||||
private static final double kAngleSetpoint = 0.0;
|
||||
@@ -28,9 +28,8 @@ public class Robot extends TimedRobot {
|
||||
private static final int kGyroPort = 0;
|
||||
private static final int kJoystickPort = 0;
|
||||
|
||||
private final DifferentialDrive m_myRobot
|
||||
= new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort),
|
||||
new PWMVictorSPX(kRightMotorPort));
|
||||
private final DifferentialDrive m_myRobot =
|
||||
new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort), new PWMVictorSPX(kRightMotorPort));
|
||||
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
|
||||
private final Joystick m_joystick = new Joystick(kJoystickPort);
|
||||
|
||||
@@ -40,8 +39,8 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
|
||||
/**
|
||||
* The motor speed is set from the joystick while the RobotDrive turning
|
||||
* value is assigned from the error between the setpoint and the gyro angle.
|
||||
* The motor speed is set from the joystick while the RobotDrive turning value is assigned from
|
||||
* the error between the setpoint and the gyro angle.
|
||||
*/
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
@@ -6,8 +6,8 @@ package edu.wpi.first.wpilibj.examples.gyrodrivecommands;
|
||||
|
||||
/**
|
||||
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
|
||||
* constants. This class should not be used for any other purpose. All constants should be
|
||||
* declared globally (i.e. public static). Do not put anything functional in this class.
|
||||
* constants. This class should not be used for any other purpose. All constants should be declared
|
||||
* globally (i.e. public static). Do not put anything functional in this class.
|
||||
*
|
||||
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
|
||||
* constants are needed, to reduce verbosity.
|
||||
@@ -19,8 +19,8 @@ public final class Constants {
|
||||
public static final int kRightMotor1Port = 2;
|
||||
public static final int kRightMotor2Port = 3;
|
||||
|
||||
public static final int[] kLeftEncoderPorts = new int[]{0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[]{2, 3};
|
||||
public static final int[] kLeftEncoderPorts = new int[] {0, 1};
|
||||
public static final int[] kRightEncoderPorts = new int[] {2, 3};
|
||||
public static final boolean kLeftEncoderReversed = false;
|
||||
public static final boolean kRightEncoderReversed = true;
|
||||
|
||||
|
||||
@@ -12,8 +12,7 @@ import edu.wpi.first.wpilibj.RobotBase;
|
||||
* call.
|
||||
*/
|
||||
public final class Main {
|
||||
private Main() {
|
||||
}
|
||||
private Main() {}
|
||||
|
||||
/**
|
||||
* Main initialization function. Do not perform any initialization here.
|
||||
|
||||
@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
|
||||
* This function is called every robot packet, no matter the mode. Use this for items like
|
||||
* diagnostics that you want ran during disabled, autonomous, teleoperated and test.
|
||||
*
|
||||
* <p>This runs after the mode specific periodic functions, but before
|
||||
* LiveWindow and SmartDashboard integrated updating.
|
||||
* <p>This runs after the mode specific periodic functions, but before LiveWindow and
|
||||
* SmartDashboard integrated updating.
|
||||
*/
|
||||
@Override
|
||||
public void robotPeriodic() {
|
||||
@@ -46,20 +46,14 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().run();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called once each time the robot enters Disabled mode.
|
||||
*/
|
||||
/** This function is called once each time the robot enters Disabled mode. */
|
||||
@Override
|
||||
public void disabledInit() {
|
||||
}
|
||||
public void disabledInit() {}
|
||||
|
||||
@Override
|
||||
public void disabledPeriodic() {
|
||||
}
|
||||
public void disabledPeriodic() {}
|
||||
|
||||
/**
|
||||
* This autonomous runs the autonomous command selected by your {@link RobotContainer} class.
|
||||
*/
|
||||
/** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
|
||||
@Override
|
||||
public void autonomousInit() {
|
||||
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
|
||||
@@ -77,12 +71,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during autonomous.
|
||||
*/
|
||||
/** This function is called periodically during autonomous. */
|
||||
@Override
|
||||
public void autonomousPeriodic() {
|
||||
}
|
||||
public void autonomousPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void teleopInit() {
|
||||
@@ -95,13 +86,9 @@ public class Robot extends TimedRobot {
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during operator control.
|
||||
*/
|
||||
/** This function is called periodically during operator control. */
|
||||
@Override
|
||||
public void teleopPeriodic() {
|
||||
|
||||
}
|
||||
public void teleopPeriodic() {}
|
||||
|
||||
@Override
|
||||
public void testInit() {
|
||||
@@ -109,10 +96,7 @@ public class Robot extends TimedRobot {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
}
|
||||
|
||||
/**
|
||||
* This function is called periodically during test mode.
|
||||
*/
|
||||
/** This function is called periodically during test mode. */
|
||||
@Override
|
||||
public void testPeriodic() {
|
||||
}
|
||||
public void testPeriodic() {}
|
||||
}
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user