Skip to content

Commit

Permalink
testing changes
Browse files Browse the repository at this point in the history
  • Loading branch information
penguin212 committed Jan 27, 2024
1 parent 2411f2b commit 451f950
Show file tree
Hide file tree
Showing 2 changed files with 25 additions and 20 deletions.
36 changes: 18 additions & 18 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -104,30 +104,30 @@ private void configureBindings() {
feederSubsystem.setFeederMotorSpeed(feederSubsystem.FEEDER_MOTOR_SPEED);
}));

bButton.onTrue(new InstantCommand(() -> {
bButton.onFalse(new InstantCommand(() -> {
feederSubsystem.setFeederMotorSpeed(0);
}));

pivotSubsystem.setDefaultCommand(new InstantCommand(() -> {
pivotSubsystem.setPivotMotorSpeed(mechController.getRightTriggerAxis() - mechController.getLeftTriggerAxis());
}));
pivotSubsystem.setPivotMotorSpeed(.3 * (mechController.getRightTriggerAxis() - mechController.getLeftTriggerAxis()));
}, pivotSubsystem));

if(baseSwerveSubsystem instanceof SwerveSubsystem){
final SwerveSubsystem swerveSubsystem = (SwerveSubsystem) baseSwerveSubsystem;

swerveSubsystem.setDefaultCommand(new RunCommand(() -> {
swerveSubsystem.setDrivePowers(driveController.getLeftPower(), driveController.getForwardPower(), driveController.getRotatePower());//, 1 * (controller.getRightTriggerAxis() - controller.getLeftTriggerAxis()));
pivotSubsystem.setFieldPosition(swerveSubsystem.getRobotPosition());
}
, swerveSubsystem));

driveController.getFieldResetButton().onTrue(new InstantCommand(() -> {
swerveSubsystem.resetDriverHeading();
}
));

final SwerveSubsystem swerveSubsystem = (SwerveSubsystem) baseSwerveSubsystem;

swerveSubsystem.setDefaultCommand(new RunCommand(() -> {
// swerveSubsystem.setDrivePowers(driveController.getLeftPower(), driveController.getForwardPower(), driveController.getRotatePower());//, 1 * (controller.getRightTriggerAxis() - controller.getLeftTriggerAxis()));
// pivotSubsystem.setFieldPosition(swerveSubsystem.getRobotPosition());
}
, swerveSubsystem));

driveController.getFieldResetButton().onTrue(new InstantCommand(() -> {
swerveSubsystem.resetDriverHeading();
}
));
} else if(baseSwerveSubsystem instanceof TestSingleModuleSwerveSubsystem){
final TestSingleModuleSwerveSubsystem testSwerveSubsystem = (TestSingleModuleSwerveSubsystem) baseSwerveSubsystem;
final TestSingleModuleSwerveSubsystem testSwerveSubsystem = (TestSingleModuleSwerveSubsystem) baseSwerveSubsystem;
// LBumper.onTrue(new InstantCommand(() -> {
// testSwerveSubsystem.decrementTest();
// System.out.println(testSwerveSubsystem.getTest());
Expand All @@ -146,7 +146,7 @@ private void configureBindings() {
// }));

} else if (baseSwerveSubsystem instanceof SingleModuleSwerveSubsystem){
final SingleModuleSwerveSubsystem swerveSubsystem = (SingleModuleSwerveSubsystem) baseSwerveSubsystem;
final SingleModuleSwerveSubsystem swerveSubsystem = (SingleModuleSwerveSubsystem) baseSwerveSubsystem;

// System.out.println("1");

Expand Down
9 changes: 7 additions & 2 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@

package frc.robot.subsystems;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.subsystems.shooter.ShooterState;
Expand All @@ -13,7 +14,7 @@ public class ShooterSubsystem extends SubsystemBase {

//change later (ALL OF THEM ARE PLACEHOLDERS)
int IDNUMBER = 10; //so I remember to change them later
public final double SHOOTER_MOTOR_SPEED = 0.1;
public final double SHOOTER_MOTOR_SPEED = 1;

//motors
private final CANSparkMax shooterMotor;
Expand All @@ -29,6 +30,10 @@ public ShooterSubsystem(){
shooterMotor = new CANSparkMax(13, MotorType.kBrushless);
shooterMotorTwo = new CANSparkMax(14, MotorType.kBrushless);

shooterMotor.setIdleMode(IdleMode.kCoast);
shooterMotorTwo.setIdleMode(IdleMode.kCoast);


//second motor shooter follows first
shooterMotorTwo.follow(shooterMotor, true);

Expand All @@ -46,7 +51,7 @@ public void setShooterState(ShooterState newState){
}

public void setShooterMotorSpeed(double speed){
shooterMotor.setVoltage(speed * 12);
shooterMotor.setVoltage(-speed * 12);
System.out.println("shooter motor speed is: " + shooterMotor.get());
}

Expand Down

0 comments on commit 451f950

Please sign in to comment.