Skip to content

Commit

Permalink
name changes
Browse files Browse the repository at this point in the history
  • Loading branch information
Craptop committed Dec 5, 2023
1 parent 9e65adb commit 8aeac1c
Show file tree
Hide file tree
Showing 9 changed files with 389 additions and 345 deletions.
120 changes: 0 additions & 120 deletions src/main/java/frc/Subsystems/ElevatorSubsystem.java

This file was deleted.

89 changes: 39 additions & 50 deletions src/main/java/frc/robot/Commands/ElevatorBaseCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,58 +2,47 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

package frc.robot.Commands;


import frc.Subsystems.ElevatorSubsystem;
import edu.wpi.first.wpilibj2.command.CommandBase;

import frc.robot.subsystems.ElevatorSubsystem;

/** An example command that uses an example subsystem. */
public class ElevatorBaseCommand extends CommandBase {
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final ElevatorSubsystem elevatorSubsystem;
public double targetHeight;


/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public ElevatorBaseCommand(ElevatorSubsystem elevatorSubsystem, double targetHeight) {
this.targetHeight = targetHeight;
this.elevatorSubsystem = elevatorSubsystem;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(elevatorSubsystem);
}


// Called when the command is initially scheduled.
@Override
public void initialize() {
elevatorSubsystem.setTargetHeight(targetHeight);




}


// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}


// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}


// Returns true when the command should end.
@Override
public boolean isFinished() {
return elevatorSubsystem.nearTargetHeight();
}
}
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
private final ElevatorSubsystem elevatorSubsystem;

public double targetHeight;

/**
* Creates a new ExampleCommand.
*
* @param subsystem The subsystem used by this command.
*/
public ElevatorBaseCommand(ElevatorSubsystem elevatorSubsystem, double targetHeight) {
this.targetHeight = targetHeight;
this.elevatorSubsystem = elevatorSubsystem;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(elevatorSubsystem);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
elevatorSubsystem.setTargetHeight(targetHeight);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return elevatorSubsystem.nearTargetHeight();
}
}
37 changes: 37 additions & 0 deletions src/main/java/frc/robot/Commands/SequentialCommands.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,37 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import frc.robot.subsystems.WristSubsystem;

public class SequentialCommands extends SequentialCommandGroup {
/** Creates a new TestCommand. */
public SequentialCommands(WristSubsystem wristSubsystem) {
// Use addRequirements() here to declare subsystem dependencies.
addCommands(
new WristCommand(wristSubsystem, 0),
new WristCommand(wristSubsystem, 20),
new WristCommand(wristSubsystem, 40));
}

// // Called when the command is initially scheduled.
// @Override
// public void initialize() {}

// // Called every time the scheduler runs while the command is scheduled.
// @Override
// public void execute() {}

// // Called once the command ends or is interrupted.
// @Override
// public void end(boolean interrupted) {}

// // Returns true when the command should end.
// @Override
// public boolean isFinished() {
// return false;
// }
}
44 changes: 44 additions & 0 deletions src/main/java/frc/robot/Commands/WristCommand.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.WristSubsystem;

public class WristCommand extends CommandBase {
/** Creates a new WristCommand. */
private final WristSubsystem wristSubsystem;

private double targetAngle;

public WristCommand(WristSubsystem wristSubsystem, double targetAngle) {
// Use addRequirements() here to declare subsystem dependencies.
this.wristSubsystem = wristSubsystem;
this.targetAngle = targetAngle;

addRequirements(wristSubsystem);
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
// sets target angle
wristSubsystem.setTargetAngle(targetAngle);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return wristSubsystem.nearTargetAngle();
}
}
40 changes: 19 additions & 21 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,30 +2,28 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.


package frc.robot;


@SuppressWarnings("java:S1118")
/**
* 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.
*
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
* constants are needed, to reduce verbosity.
*/
* 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.
*
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
}
public static class Elevator{
/**the gear ratio of the motor to the final gear revolutions */
public static final double GEAR_RATIO = 0.1008;
/**The number of ticks per motor revolution */
public static final double TICKS_PER_REVOLUTION = 2048;
/**The gear circumferance for distance */
public static final double GEAR_CIRCUMFERENCE = 1.432*Math.PI;

public static class OperatorConstants {
public static final int kDriverControllerPort = 0;
}

public static class Elevator {
/** the gear ratio of the motor to the final gear revolutions */
public static final double GEAR_RATIO = 0.1008;
/** The number of ticks per motor revolution */
public static final double TICKS_PER_REVOLUTION = 2048;
/** The gear circumferance for distance */
public static final double GEAR_CIRCUMFERENCE = 1.432 * Math.PI;
}
}
}
Loading

0 comments on commit 8aeac1c

Please sign in to comment.