Skip to content
This repository has been archived by the owner on Feb 12, 2025. It is now read-only.

Commit

Permalink
well shit
Browse files Browse the repository at this point in the history
the cims ain't working
  • Loading branch information
MKECyberCheese committed Mar 18, 2023
1 parent 60a6d86 commit b8db209
Show file tree
Hide file tree
Showing 7 changed files with 66 additions and 24 deletions.
1 change: 1 addition & 0 deletions .DataLogTool/datalogtool.json
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
{}
10 changes: 6 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -87,8 +87,10 @@ public static final class drive {
public static final DifferentialDrive m_drive = new DifferentialDrive(m_leftMotorController,
m_rightMotorController);

public static final double DRIVE_SPEED = 0.8;
public static final double TURN_SPEED = 0.8;
public static final int CURRENT_LIMIT = 50;

public static final double DRIVE_SPEED = 1;
public static final double TURN_SPEED = 1;

public static final boolean LEFT_FRONT_INVERTED = false;
public static final boolean LEFT_REAR_INVERTED = false;
Expand All @@ -105,8 +107,8 @@ public static final class intake {
public static final double CONE_SPEED = 0.3;
public static final double CUBE_SPEED = -0.3;

public static final Value intakeDown = Value.kReverse;
public static final Value intakeUp = Value.kForward;
public static final Value intakeDown = Value.kForward;
public static final Value intakeUp = Value.kReverse;
public static final Value intakeOff = Value.kOff;
}

Expand Down
19 changes: 2 additions & 17 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -138,28 +138,13 @@ public void teleopInit() {
// also accurate
m_leftElevator.zero();
m_rightElevator.zero();
new First(m_shifter);
new Second(m_shifter);
}

/** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {
if (RobotContainer.m_filteredController.getPOVPressed().getAsBoolean()) {
new Runnable() {
@Override
public void run() {
if (!RobotContainer.readAuto) {
RobotContainer.readAuto = true;
m_autoSubsystem.clearShit();
System.out.println("Started - Begin Tracking Autonomous");
} else {
RobotContainer.readAuto = false;
System.out.println("Ended - Finished Tracking Autonomous");
m_autoSubsystem.printSpeeds();
}
}
};
}

}

@Override
Expand Down
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import frc.robot.commands.IntakeCubeCommand;
import frc.robot.commands.IntakeDown;
import frc.robot.commands.IntakeUp;
import frc.robot.commands.RecordAuto;
import frc.robot.commands.Second;
import frc.robot.commands.ZeroSlides;
import frc.robot.commands.ArcadeDrive;
Expand Down Expand Up @@ -129,6 +130,8 @@ private void configureButtonBindings() {
xButton.onTrue(new IntakeDown(m_intake));
yButton.onTrue(new IntakeUp(m_intake));

POV.debounce(0.2).whileTrue(new RecordAuto(m_autoSubsystem));

}

}
1 change: 0 additions & 1 deletion src/main/java/frc/robot/commands/AutoCommand.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
package frc.robot.commands;

import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.subsystems.AutoSubsystem;

Expand Down
40 changes: 40 additions & 0 deletions src/main/java/frc/robot/commands/RecordAuto.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,40 @@
package frc.robot.commands;

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

public class RecordAuto extends CommandBase {
private final AutoSubsystem m_autoSubsystem;

//constructor
public RecordAuto(AutoSubsystem autoSubsystem) {
this.m_autoSubsystem = autoSubsystem;
}

@Override
public void initialize() {

if (!RobotContainer.readAuto) {
RobotContainer.readAuto = true;
m_autoSubsystem.clearShit();
System.out.println("Started - Begin Tracking Autonomous");
} else {
RobotContainer.readAuto = false;
System.out.println("Ended - Finished Tracking Autonomous");
m_autoSubsystem.printSpeeds();
}
}



/**
* This function ensures when the action is complete, the robot stops moving
*
* @param interrupted
*/
@Override
public void end(boolean interrupted) {

}
}
16 changes: 14 additions & 2 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@ public Drivetrain() {
Constants.controllers.leftRearSpark.setInverted(Constants.drive.LEFT_REAR_INVERTED);
Constants.controllers.rightFrontSpark.setInverted(Constants.drive.RIGHT_FRONT_INVERTED);
Constants.controllers.rightRearSpark.setInverted(Constants.drive.RIGHT_REAR_INVERTED);
Constants.controllers.leftFrontSpark.setSmartCurrentLimit(Constants.drive.CURRENT_LIMIT);
Constants.controllers.rightFrontSpark.setSmartCurrentLimit(Constants.drive.CURRENT_LIMIT);
Constants.controllers.leftRearSpark.setSmartCurrentLimit(Constants.drive.CURRENT_LIMIT);
Constants.controllers.rightRearSpark.setSmartCurrentLimit(Constants.drive.CURRENT_LIMIT);
// Encoders may measure differently in the real world and in
// simulation. In this example the robot moves 0.042 barleycorns
// per tick in the real world, but the simulated encoders
Expand All @@ -52,13 +56,21 @@ public void log() {
SmartDashboard.putNumber("Left Speed", Constants.sensors.m_leftDriveEncoder.getRate());
SmartDashboard.putNumber("Right Speed", Constants.sensors.m_rightDriveEncoder.getRate());
SmartDashboard.putData("Drivetrain", Constants.drive.m_drive);
SmartDashboard.putNumber("FrontLeft Temp", Constants.controllers.leftFrontSpark.getMotorTemperature());
SmartDashboard.putNumber("BackLeft Temp", Constants.controllers.leftRearSpark.getMotorTemperature());
SmartDashboard.putNumber("FrontRight Temp", Constants.controllers.rightFrontSpark.getMotorTemperature());
SmartDashboard.putNumber("BackRight Temp", Constants.controllers.rightRearSpark.getMotorTemperature());
SmartDashboard.putNumber("FrontLeft Current", Constants.controllers.leftFrontSpark.getOutputCurrent());
SmartDashboard.putNumber("BackLeft Current", Constants.controllers.leftRearSpark.getOutputCurrent());
SmartDashboard.putNumber("FrontRight Current", Constants.controllers.rightFrontSpark.getOutputCurrent());
SmartDashboard.putNumber("BackRight Current", Constants.controllers.rightRearSpark.getOutputCurrent());
}

/**
* Tank style driving for the Drivetrain.
* Arcade style driving for the Drivetrain.
*
* @param throttle Speed in range [-1,1]
* @param turn Speed in range [-1,1]
* @param rotation Speed in range [-1,1]
*/
public void drive(double throttle, double rotation) {
this.throttle = throttle;
Expand Down

0 comments on commit b8db209

Please sign in to comment.