Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
32 changes: 0 additions & 32 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -119,39 +119,8 @@ public static class Intake {
public static final double k_feedShooterSpeed = -0.5;
}

// PCM
public static final int kPCMId = 0;
public static final int kIntakeSolenoidForwardId = 2;

// DIO

// Shooter
public static final int kShooterLeftMotorId = 12;
public static final int kShooterRightMotorId = 13;

public static final double kShooterP = 0.00005;
public static final double kShooterI = 0.0;
public static final double kShooterD = 0.0;
public static final double kShooterFF = 0.0002;

public static final double kShooterMinOutput = 0;
public static final double kShooterMaxOutput = 1;

// Climber
public static final int kClimberLeftMotorId = 14;
public static final int kClimberRightMotorId = 15;
public static final double kClimberClimbSpeed = 600.0; // RPM
public static final double kClimberReleaseSpeed = -600.0; // RPM

public static final double kClimberGearRatio = 1.0 / 12.0;

public static final double kClimberP = 0.001;
public static final double kClimberI = 0.0;
public static final double kClimberD = 0.0;
public static final double kClimberMinOutput = -0.5;

public static final double kClimberMaxOutput = 0.5;

// Drivetrain
public static class Drive {
public static final double kP = 0.0; // 0.00085;
Expand All @@ -172,7 +141,6 @@ public static class Field {
public static final double k_width = Units.feetToMeters(54.0);
public static final double k_length = Units.feetToMeters(27.0);

// TODO: Add left and right subwoofer starting poses
public static final Pose2d redCenterPose2d = new Pose2d(15.19, 5.50, new Rotation2d(Units.degreesToRadians(180.0)));
public static final Pose2d blueCenterPose2d = new Pose2d(1.27, 5.50, new Rotation2d(0));
}
Expand Down
100 changes: 2 additions & 98 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.util.Color;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.sysid.SysIdRoutine;
import frc.robot.autonomous.AutoRunner;
Expand All @@ -26,7 +25,6 @@
import frc.robot.controls.controllers.OperatorController;
import frc.robot.simulation.Field;
import frc.robot.subsystems.Algae;
import frc.robot.subsystems.Compressor;
import frc.robot.subsystems.Coral;
import frc.robot.subsystems.Drivetrain;
import frc.robot.subsystems.Elevator;
Expand All @@ -53,12 +51,9 @@ public class Robot extends LoggedRobot {

// Robot subsystems
private List<Subsystem> m_allSubsystems = new ArrayList<>();
// private final Intake m_intake = Intake.getInstance();
private final Compressor m_compressor = Compressor.getInstance();
private final Drivetrain m_drive = Drivetrain.getInstance();
private final Coral m_coral = Coral.getInstance();
private final Algae m_algae = Algae.getInstance();
// private final Shooter m_shooter = Shooter.getInstance();
private final Elevator m_elevator = Elevator.getInstance();

public final LEDs m_leds = LEDs.getInstance();
Expand Down Expand Up @@ -145,16 +140,9 @@ public void teleopInit() {

@Override
public void teleopPeriodic() {
// Get the x speed. We are inverting this because Xbox controllers return
// negative values when we push forward.
double maxSpeed = m_driverController.getWantsSpeedMode() ? Drivetrain.kMaxBoostSpeed : Drivetrain.kMaxSpeed;
double xSpeed = m_speedLimiter.calculate(m_driverController.getForwardAxis() * maxSpeed);

// 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
// mathematics). Xbox controllers return positive values when you pull to
// the right by default.

// m_drive.slowMode(m_driverController.getWantsSlowMode());
// m_drive.speedMode(m_driverController.getWantsSpeedMode());
double rot = m_rotLimiter.calculate(m_driverController.getTurnAxis() * Drivetrain.kMaxAngularSpeed);
Expand Down Expand Up @@ -199,92 +187,16 @@ public void teleopPeriodic() {
m_elevator.goToElevatorStow();
}

// ALGAE
// if (m_driverController.getWantsAlgaeStow()) {
// m_algae.stow();
// } else if (m_driverController.getWantsAlgaeGrab()) {
// m_algae.grabAlgae();
// } else if (m_driverController.getWantsAlgaeScore()) {
// m_algae.score();
// } else if (m_driverController.getWantsAlgaeGroundIntake()) {
// m_algae.groundIntake();
// }

// ELEVATOR
// m_elevator.setElevatorPower(m_operatorController.getElevatorAxis());
// if (m_operatorController.getWantsElevatorStow()) {
// m_elevator.goToElevatorStow();
// } else if (m_operatorController.getWantsElevatorL2()) {
// m_elevator.goToElevatorL2();
// } else if (m_operatorController.getWantsElevatorL3()) {
// m_elevator.goToElevatorL3();
// } else if (m_operatorController.getWantsElevatorL4()) {
// m_elevator.goToElevatorL4();
// }

// CORAL
// if (m_operatorController.getWantsCoralIntake()) {
// m_coral.intake();
// } else if (m_operatorController.getWantsCoralReverse()) {
// m_coral.reverse();
// } else if (m_operatorController.getWantsCoralIndex()) {
// m_coral.index();
// } else if (m_operatorController.getWantsCoralL1()) {
// m_coral.scoreL1();
// } else if (m_operatorController.getWantsCoralL24()) {
// m_coral.scoreL24();
// } else {
// m_coral.stopCoral();
// }

if (m_operatorController.getWantsElevatorReset() || m_driverController.getWantsElevatorReset()) {
RobotTelemetry.print("Resetting elevator");
m_elevator.reset();
}

// // Intake
// if (m_driverController.getWantsFullIntake()) {
// m_intake.goToGround();
// } else if (m_driverController.getWantsIntake()) {
// if (m_intake.getIntakeHasNote()) {
// m_intake.pulse();
// } else {
// m_intake.intake();
// }
// } else if (m_driverController.getWantsEject()) {
// m_intake.eject();
// } else if (m_driverController.getWantsSource()) {
// m_intake.goToSource();
// } else if (m_driverController.getWantsStow()) {
// m_intake.goToStow();
// } else if (m_intake.getIntakeState() != IntakeState.INTAKE) {
// m_intake.stopIntake();
// }

// // Climber
// if (m_operatorController.getWantsClimberClimb()) {
// m_climber.climb();
// } else if (m_operatorController.getWantsClimberRelease()) {
// m_climber.release();
// } else if (m_operatorController.getWantsClimberTiltLeft()) {
// m_climber.tiltLeft();
// } else if (m_operatorController.getWantsClimberTiltRight()) {
// m_climber.tiltRight();
// } else {
// m_climber.stopClimber();
// }

// if (m_operatorController.getWantsBrakeMode()) {
// m_climber.setBrakeMode();
// } else if (m_operatorController.getWantsCoastMode()) {
// m_climber.setCoastMode();
// }
}

@Override
public void disabledInit() {
// m_leds.rainbow();
m_leds.setColor(Color.kRed);
m_leds.rainbow();
// m_leds.setColor(Color.kRed);

speed = 0;
m_allSubsystems.forEach(subsystem -> subsystem.stop());
Expand Down Expand Up @@ -349,14 +261,6 @@ private void setupLogging() {
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
new PowerDistribution(1, ModuleType.kCTRE); // Enables power distribution logging
}
// else {
// setUseTiming(false); // Run as fast as possible
// String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from
// AdvantageScope (or prompt the user)
// Logger.setReplaySource(new WPILOGReader(logPath)); // Read replay log
// Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath,
// "_sim"))); // Save outputs to a new log
// }

Logger.start();
}
Expand Down
27 changes: 11 additions & 16 deletions src/main/java/frc/robot/autonomous/tasks/DriveTrajectoryTask.java
Original file line number Diff line number Diff line change
@@ -1,13 +1,9 @@
package frc.robot.autonomous.tasks;

import static edu.wpi.first.units.Units.Kilogram;
import static edu.wpi.first.units.Units.MetersPerSecond;

import java.nio.file.Path;

import org.littletonrobotics.junction.Logger;

import com.pathplanner.lib.config.RobotConfig;
import com.pathplanner.lib.controllers.PPLTVController;
import com.pathplanner.lib.path.PathPlannerPath;
import com.pathplanner.lib.trajectory.PathPlannerTrajectory;
Expand All @@ -17,9 +13,6 @@
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.units.measure.Mass;
import edu.wpi.first.units.measure.Velocity;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.DriverStation.Alliance;
import edu.wpi.first.wpilibj.Filesystem;
Expand Down Expand Up @@ -70,15 +63,15 @@ public DriveTrajectoryTask(String pathName) {
m_autoPath,
new ChassisSpeeds(),
m_drive.getPose().getRotation(),
m_drive.getRobotConfig()
);
m_drive.getRobotConfig());

if (m_autoPath.isReversed()) {
RobotTelemetry.print("===== PATH IS REVERSED =====");
}

double rotationErrorTolerance = Math.pow(m_autoPath.getGlobalConstraints().maxVelocityMPS(), 1.25) * 0.25;
// double translationErrorTolerance = m_autoPath.getGlobalConstraints().getMaxVelocityMps() * 0.0625;
// double translationErrorTolerance =
// m_autoPath.getGlobalConstraints().getMaxVelocityMps() * 0.0625;

m_driveController = new PPLTVController(
VecBuilder.fill(0.25, 0.25, 1.0),
Expand Down Expand Up @@ -126,13 +119,15 @@ public void start() {

// DEBUG Trajectory //////////////////////////////////////////////
// Trajectory adjustedTrajectory = TrajectoryGenerator.generateTrajectory(
// m_autoPath.getPathPoses(),
// new TrajectoryConfig(
// m_autoPath.getGlobalConstraints().getMaxVelocityMps(),
// m_autoPath.getGlobalConstraints().getMaxAccelerationMpsSq()));
// Logger.recordOutput("Auto/DriveTrajectory/TargetTrajectory", adjustedTrajectory);
// m_autoPath.getPathPoses(),
// new TrajectoryConfig(
// m_autoPath.getGlobalConstraints().getMaxVelocityMps(),
// m_autoPath.getGlobalConstraints().getMaxAccelerationMpsSq()));
// Logger.recordOutput("Auto/DriveTrajectory/TargetTrajectory",
// adjustedTrajectory);
// if (shouldReplan) {
// Logger.recordOutput("Auto/DriveTrajectory/ReplannedTrajectory", adjustedTrajectory);
// Logger.recordOutput("Auto/DriveTrajectory/ReplannedTrajectory",
// adjustedTrajectory);
// }
/////////////////////////////////////////////////////////////////

Expand Down
32 changes: 0 additions & 32 deletions src/main/java/frc/robot/autonomous/tasks/IntakeTask.java

This file was deleted.

27 changes: 0 additions & 27 deletions src/main/java/frc/robot/autonomous/tasks/ShooterTask.java

This file was deleted.

Loading