Skip to content
This repository has been archived by the owner on Jan 10, 2024. It is now read-only.

Commit

Permalink
final commit before buckeye
Browse files Browse the repository at this point in the history
  • Loading branch information
TheGamer1002 committed Mar 28, 2023
1 parent b78f058 commit e377eac
Show file tree
Hide file tree
Showing 5 changed files with 8 additions and 7 deletions.
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -141,9 +141,9 @@ public static double getDriverControllerRightStickX() {
public static double getDriverControllerRightStickXAdjusted() {
double val = getDriverControllerRightStickX();
if (val > 0) {
return (val * val + 0.3) / 1.3;
return (val * val + 0.1) / 1.1;
} else if (val < 0) {
return -(val * val + 0.3) / 1.3;
return -(val * val + 0.1) / 1.1;
} else {
return 0;
}
Expand Down
5 changes: 3 additions & 2 deletions src/main/java/frc/robot/commands/AutoCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,9 @@

public class AutoCommand extends SequentialCommandGroup {
public AutoCommand(PID m_pid, Tank m_driveBase, Arm m_arm, Claw m_claw) {
addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm, m_claw));
addCommands(new BalanceCommand(m_pid, m_driveBase));
addCommands(new PlaceConeSecondLevelCommand(m_driveBase, m_arm, m_claw), new BalanceCommand(m_pid, m_driveBase));

// new BalanceCommand(m_pid, m_driveBase)
// new PlaceCubeFirstLevelCommand(m_driveBase, m_claw, m_arm)
// new PlaceConeSecondLevelCommand(m_driveBase, m_arm)
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/BalanceCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ public void execute() {
SmartDashboard.putNumber("max offset", max);

if (pitchOffset < 16 && !onRamp) {
driveBase.setAllMotors(0.25);
driveBase.setAllMotors(0.5);
SmartDashboard.putBoolean("onRamp", onRamp);

} else {
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/DriveCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ public void execute() {
// double check getMaxSpeed(), might be wrong
Tank.arcadeDrive(
RobotContainer.getDriverControllerLeftStickYAdjusted() * Constants.CanConstants.maxSpeed,
RobotContainer.getDriverControllerRightStickXAdjusted() * 0.75);
RobotContainer.getDriverControllerRightStickXAdjusted() * 0.7);

SmartDashboard.putNumber("maxSpeed", Constants.CanConstants.maxSpeed);
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/MoveArmYCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public void initialize() {}

@Override
public void execute() {
m_subsystem.moveArm(RobotContainer.getControllerLeftStickY());
m_subsystem.moveArm(-RobotContainer.getControllerLeftStickY());
}

@Override
Expand Down

0 comments on commit e377eac

Please sign in to comment.