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
10 changes: 5 additions & 5 deletions src/main/deploy/pathplanner/1 Piece Mobility Dock.path
Original file line number Diff line number Diff line change
Expand Up @@ -2,12 +2,12 @@
"waypoints": [
{
"anchorPoint": {
"x": 2.11,
"x": 1.956147399839285,
"y": 2.2
},
"prevControl": null,
"nextControl": {
"x": 3.1100000000000003,
"x": 2.9561473998392858,
"y": 2.2
},
"holonomicAngle": 0.0,
Expand Down Expand Up @@ -49,15 +49,15 @@
},
{
"anchorPoint": {
"x": 6.27,
"x": 6.1694,
"y": 2.21
},
"prevControl": {
"x": 6.4868342815896725,
"x": 6.386234281589673,
"y": 2.21
},
"nextControl": {
"x": 6.4868342815896725,
"x": 6.386234281589673,
"y": 2.21
},
"holonomicAngle": 0.0,
Expand Down
18 changes: 9 additions & 9 deletions src/main/deploy/pathplanner/3 Piece Blue.path
Original file line number Diff line number Diff line change
Expand Up @@ -25,15 +25,15 @@
{
"anchorPoint": {
"x": 6.340000000000001,
"y": 4.44
"y": 4.74
},
"prevControl": {
"x": 5.587270042913402,
"y": 4.44
"y": 4.74
},
"nextControl": {
"x": 6.549202411287385,
"y": 4.44
"y": 4.74
},
"holonomicAngle": 0,
"isReversal": false,
Expand All @@ -50,15 +50,15 @@
{
"anchorPoint": {
"x": 6.7700000000000005,
"y": 4.44
"y": 4.74
},
"prevControl": {
"x": 6.651547629778109,
"y": 4.471296466187375
"y": 4.771296466187375
},
"nextControl": {
"x": 6.651547629778109,
"y": 4.471296466187375
"y": 4.771296466187375
},
"holonomicAngle": 0,
"isReversal": true,
Expand Down Expand Up @@ -100,15 +100,15 @@
{
"anchorPoint": {
"x": 6.58,
"y": 3.53
"y": 3.73
},
"prevControl": {
"x": 5.370212645435206,
"y": 4.73978735456479
"y": 4.93978735456479
},
"nextControl": {
"x": 6.712618407320928,
"y": 3.3973815926790722
"y": 3.5973815926790722
},
"holonomicAngle": -30.0,
"isReversal": false,
Expand Down
9 changes: 7 additions & 2 deletions src/main/java/com/stuypulse/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -154,8 +154,7 @@ private void configureDriverBindings() {
.debounce(0.5, DebounceType.kFalling)
.onTrue(new LEDSet(LEDColor.RED))
.onTrue(new InstantCommand(() -> driver.setRumble(0.5)))
.onFalse(new InstantCommand(() -> driver.setRumble(0.0)))
;
.onFalse(new InstantCommand(() -> driver.setRumble(0.0)));
}

private void configureOperatorBindings() {
Expand Down Expand Up @@ -224,6 +223,12 @@ private void configureOperatorBindings() {
// arm to neutral
operator.getDPadRight().onTrue(new IntakeAcquire())
.onFalse(new IntakeStop());

new Trigger(intake::hasGamePiece)
.and(DriverStation::isTeleop)
.debounce(0.5, DebounceType.kFalling)
.onTrue(new InstantCommand(() -> operator.setRumble(0.5)))
.onFalse(new InstantCommand(() -> operator.setRumble(0.0)));
}

/**************/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,6 @@
import com.stuypulse.robot.commands.plant.PlantEngage;
import com.stuypulse.robot.commands.swerve.*;
import com.stuypulse.robot.commands.swerve.balance.SwerveDriveBalanceBlay;
import com.stuypulse.robot.subsystems.Manager;
import com.stuypulse.robot.subsystems.Manager.*;
import com.stuypulse.robot.util.ArmState;
import com.stuypulse.robot.util.ArmTrajectory;
Expand All @@ -27,26 +26,6 @@

public class OnePieceMobilityDock extends DebugSequentialCommandGroup {

static class ConeAutonReady extends ArmRoutine {
public ConeAutonReady() {
super(() -> {
if (Manager.getInstance().getNodeLevel() == NodeLevel.HIGH)
return new ArmState(-179, 136 - 8);
else
return new ArmState(-161.7, 133.9);
});
}

@Override
protected ArmTrajectory getTrajectory(ArmState src, ArmState dest) {
return new ArmTrajectory()
.addState(
new ArmState(dest.getShoulderDegrees(), src.getWristDegrees())
.setWristLimp(true))
.addState(dest);
}
}

private class FastStow extends ArmRoutine {
public FastStow() {
super(() -> new ArmState(-90, 90)
Expand All @@ -70,21 +49,24 @@ protected ArmTrajectory getTrajectory(ArmState src, ArmState dest) {

public OnePieceMobilityDock() {
var paths = SwerveDriveFollowTrajectory.getSeparatedPaths(
PathPlanner.loadPathGroup("1 Piece Mobility Dock", OVER_CHARGE, DOCK),
PathPlanner.loadPathGroup("1 Piece + Mobility Dock", OVER_CHARGE, DOCK),
"Over Charge", "Dock"
);

// initial setup
addCommands(
new ManagerSetNodeLevel(NodeLevel.MID),
new ManagerSetNodeLevel(NodeLevel.HIGH),
new ManagerSetGamePiece(GamePiece.CONE_TIP_UP),
new ManagerSetScoreSide(ScoreSide.BACK)
);

// score first piece
addCommands(
new LEDSet(LEDColor.RED),
new ConeAutonReady()
new ArmReady()
.setWristVelocityTolerance(25)
.setShoulderVelocityTolerance(45)
.withTolerance(7, 9)
.withTimeout(3)
);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ public ArmIntakeFirst() {
@Override
protected ArmTrajectory getTrajectory(ArmState src, ArmState dest) {
dest = new ArmState(
-70.82,
-70.82 - 2,
11);
// 8.37);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,7 @@ public ArmIntakeFirst() {
@Override
protected ArmTrajectory getTrajectory(ArmState src, ArmState dest) {
dest = new ArmState(
-70.82,
-70.82 - 2,
11);
// 8.37);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,10 +15,10 @@ public interface ArmTrajectories {

public interface Acquire {
ArmState kCone = new ArmState(
new SmartNumber("Arm Trajectories/Acquire Cone Shoulder", -75),
new SmartNumber("Arm Trajectories/Acquire Cone Wrist", 12));
new SmartNumber("Arm Trajectories/Acquire Cone Shoulder", -78),
new SmartNumber("Arm Trajectories/Acquire Cone Wrist", 11));
ArmState kCube = new ArmState(
new SmartNumber("Arm Trajectories/Acquire Cube Shoulder", -75),
new SmartNumber("Arm Trajectories/Acquire Cube Shoulder", -78),
new SmartNumber("Arm Trajectories/Acquire Cube Wrist", 12));

ArmState kHPCone = new ArmState(
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/stuypulse/robot/constants/Settings.java
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ public interface Drive {

public interface FrontRight {
String ID = "Front Right";
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(122.605534) // recalibrated 10/1
Rotation2d ABSOLUTE_OFFSET = Rotation2d.fromDegrees(122.949092) // recalibrated 11/11
.plus(Rotation2d.fromDegrees(0));
Translation2d MODULE_OFFSET = new Translation2d(WIDTH * +0.5, LENGTH * -0.5);
}
Expand Down