Skip to content

Commit

Permalink
workshop 9/29
Browse files Browse the repository at this point in the history
  • Loading branch information
ControlsNarwhal committed Sep 30, 2023
1 parent dc969b8 commit 9ab8d76
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 14 deletions.
12 changes: 6 additions & 6 deletions src/main/java/frc/team3128/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -500,14 +500,14 @@ public static class WristConstants {
public static final double kV = 0;
public static final double kG = 0.22;

public static final double GEAR_RATIO = 3.0;
public static final double GEAR_RATIO = 90;

public static final double ROTATION_TO_DEGREES = 360;

public static final double ANGLE_OFFSET = 0;

public static final int MIN_ANGLE = -90;
public static final int MAX_ANGLE = 70;
public static final int MAX_ANGLE = 90;

public static final double WRIST_TOLERANCE = 0.5;

Expand All @@ -519,11 +519,11 @@ public static class ManipulatorConstants{
public static final int ROLLER_MOTOR_ID = 31;
public static final double ROLLER_POWER = 0.9;
public static final double STALL_POWER_CONE = 0.15;
public static final double STALL_POWER_CUBE = 0.0;
public static final double STALL_POWER_CUBE = 0.90;


public static final double CURRENT_THRESHOLD_CONE = 13;
public static final double CURRENT_THRESHOLD_CUBE = 9;
public static final double CURRENT_THRESHOLD_CONE = 15;
public static final double CURRENT_THRESHOLD_CUBE = 12;
}

public static class ElevatorConstants {
Expand All @@ -538,7 +538,7 @@ public static class ElevatorConstants {
public static final double kV = 0;
public static final double kG = 0.625;

public static final double MIN_DIST = 5; //Ask Charlie
public static final double MIN_DIST = 2; //Ask Charlie
public static final double MAX_DIST = 55; //Ask Charlie

public static final double GEAR_RATIO = 12.5;
Expand Down
12 changes: 6 additions & 6 deletions src/main/java/frc/team3128/PositionConstants.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,19 +2,19 @@

public class PositionConstants {
public static enum Position {
HIGH_CONE(10, 45, true),
HIGH_CUBE(10, 45, false),
HIGH_CONE(53, -10, true),
HIGH_CUBE(50, 15, false),
MID_CONE(10, 45, true),
MID_CUBE(10, 45, false),
LOW(10, 45, true),
MID_CUBE(25, 25, false),
LOW(3, 45, true),

SHELF_CONE(10, 45, true),
SHELF_CUBE(10, 45, false),
CHUTE_CONE(10, 45, true),
CHUTE_CONE(10, 55, true),
CHUTE_CUBE(10, 45, false),

GROUND_CONE(10, 45, true),
GROUND_CUBE(10, 45, false),
GROUND_CUBE(3, 0, false),

NEUTRAL(5, 45, false);

Expand Down
8 changes: 8 additions & 0 deletions src/main/java/frc/team3128/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -110,6 +110,14 @@ private void configureButtonBindings() {
rightStick.getButton(3).onTrue(moveElv(-0.4)).onFalse(moveElv(0));
rightStick.getButton(4).onTrue(moveElevator(30));
rightStick.getButton(5).onTrue(resetElevator());
rightStick.getButton(6).onTrue(moveWri(0.4)).onFalse(moveWri(0));
rightStick.getButton(7).onTrue(moveWri(-0.4)).onFalse(moveWri(0));
rightStick.getButton(8).onTrue(moveWrist(30));
rightStick.getButton(9).onTrue(resetWrist());
rightStick.getButton(10).onTrue(intake(true));
rightStick.getButton(11).onTrue(intake(false));
rightStick.getButton(12).onTrue(outtake());
rightStick.getButton(13).onTrue(stopManip());


buttonPad.getButton(5).onTrue(
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/team3128/commands/CmdSwerveDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,7 +48,7 @@ public void execute() {
translation = translation.rotateBy(Rotation2d.fromDegrees(-90));
}

rotation = zAxis.getAsDouble() * maxAngularVelocity * swerve.throttle;
rotation = -zAxis.getAsDouble() * maxAngularVelocity * swerve.throttle;

Rotation2d driveAngle = translation.getAngle();
double slowedDist = accelLimiter.calculate(translation.getNorm());
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/team3128/subsystems/Wrist.java
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ private void configMotor() {
m_wrist.setInverted(false);
m_wrist.setIdleMode(IdleMode.kBrake);
m_wrist.setSmartCurrentLimit(40);
resetEncoder();
// resetEncoder();
}

@Override
Expand All @@ -61,6 +61,7 @@ public void resetEncoder() {
}

public void set(double power) {
disable();
m_wrist.set(power);
}

Expand Down

0 comments on commit 9ab8d76

Please sign in to comment.