Skip to content

Commit

Permalink
cycle and auton tests
Browse files Browse the repository at this point in the history
  • Loading branch information
cherriae committed Mar 26, 2024
1 parent 4fcdfef commit e7cc04d
Show file tree
Hide file tree
Showing 11 changed files with 34 additions and 34 deletions.
6 changes: 3 additions & 3 deletions src/main/deploy/pathplanner/autos/3 Piece Auton Line.auto
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
{
"type": "named",
"data": {
"name": "actuateIn"
"name": "actuateInFast"
}
},
{
Expand All @@ -42,9 +42,9 @@
}
},
{
"type": "path",
"type": "named",
"data": {
"pathName": "l shoot top"
"name": "actuateInFast"
}
},
{
Expand Down
6 changes: 3 additions & 3 deletions src/main/deploy/pathplanner/autos/4 Piece Auton Line.auto
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
{
"type": "named",
"data": {
"name": "actuateIn"
"name": "actuateInFast"
}
},
{
Expand All @@ -42,9 +42,9 @@
}
},
{
"type": "path",
"type": "named",
"data": {
"pathName": "l shoot top"
"name": "actuateInFast"
}
},
{
Expand Down
14 changes: 7 additions & 7 deletions src/main/deploy/pathplanner/paths/l get top.path
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,20 @@
},
"prevControl": null,
"nextControl": {
"x": 1.8922966222509021,
"y": 6.05543748727137
"x": 1.585543742516057,
"y": 5.89310207191843
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 2.45,
"y": 7.02
"x": 2.2598788054718972,
"y": 6.963242497913567
},
"prevControl": {
"x": 2.17799714878709,
"y": 6.776367426608728
"x": 1.5420171268913974,
"y": 6.715912043252659
},
"nextControl": null,
"isLocked": false,
Expand All @@ -33,7 +33,7 @@
"eventMarkers": [
{
"name": "New Event Marker",
"waypointRelativePos": 0.2,
"waypointRelativePos": 0.0,
"command": {
"type": "sequential",
"data": {
Expand Down
12 changes: 6 additions & 6 deletions src/main/deploy/pathplanner/paths/l get topcen.path
Original file line number Diff line number Diff line change
Expand Up @@ -3,13 +3,13 @@
"waypoints": [
{
"anchor": {
"x": 2.41,
"y": 5.51
"x": 2.26,
"y": 6.96
},
"prevControl": null,
"nextControl": {
"x": 2.3074229932249173,
"y": 7.220113178969543
"x": 3.989694836537385,
"y": 7.183134366264898
},
"isLocked": false,
"linkedName": null
Expand All @@ -20,8 +20,8 @@
"y": 7.432741351973637
},
"prevControl": {
"x": 6.62469937552543,
"y": 7.441986055147727
"x": 6.525781051566957,
"y": 7.315069487277998
},
"nextControl": null,
"isLocked": false,
Expand Down
12 changes: 6 additions & 6 deletions src/main/deploy/pathplanner/paths/l shoot topcen.path
Original file line number Diff line number Diff line change
Expand Up @@ -8,20 +8,20 @@
},
"prevControl": null,
"nextControl": {
"x": 6.343113382623161,
"y": 7.3837764841295455
"x": 6.305889183206938,
"y": 7.3443884030625215
},
"isLocked": false,
"linkedName": null
},
{
"anchor": {
"x": 2.41,
"y": 5.51
"x": 2.421132842265685,
"y": 6.933923582132878
},
"prevControl": {
"x": 2.2981782900502736,
"y": 7.506698977361919
"x": 4.019013752313219,
"y": 7.1391559925977
},
"nextControl": null,
"isLocked": false,
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ public static class Speeds {
public static final double INTAKE_FEED_SPEED = 0.6; // TODO: Get this
public static final double OUTTAKE_FEED_SPEED = -0.4;

public static final double INTAKE_ACTUATE_MAX_SPEED = 0.6;
public static final double INTAKE_ACTUATE_MAX_SPEED = 0.4;
}

public static class Physical {
Expand Down Expand Up @@ -152,7 +152,7 @@ public static class Presets {
public static final InterpolatingDoubleTreeMap SHOOTER_DISTANCE_ANGLE = new InterpolatingDoubleTreeMap();

static {
SHOOTER_DISTANCE_ANGLE.put(1.359, 48.75);
SHOOTER_DISTANCE_ANGLE.put(0.735, 57.50);
SHOOTER_DISTANCE_ANGLE.put(1.755, 43.78);
SHOOTER_DISTANCE_ANGLE.put(1.823, 43.44);
SHOOTER_DISTANCE_ANGLE.put(2.543, 38.15);
Expand All @@ -164,7 +164,7 @@ public static class Presets {
public static final InterpolatingDoubleTreeMap ELEVATOR_DISTANCE_HEIGHT = new InterpolatingDoubleTreeMap();

static {
ELEVATOR_DISTANCE_HEIGHT.put(1.359, 0.078);
ELEVATOR_DISTANCE_HEIGHT.put(0.735, 0.078);
ELEVATOR_DISTANCE_HEIGHT.put(1.755, 0.061);
ELEVATOR_DISTANCE_HEIGHT.put(1.823, 0.031);
ELEVATOR_DISTANCE_HEIGHT.put(2.543, 0.024);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public void robotInit() {
PortForwarder.add(5801, "limelight.local", 5801);
PortForwarder.add(5805, "limelight.local", 5805);

CameraServer.startAutomaticCapture(0);
// CameraServer.startAutomaticCapture(0);
UtilFuncs.LoadField();

// Instantiate our RobotContainer. This will perform all our button bindings,
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/commands/auto/AutonShoot.java
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ public AutonShoot(
new ParallelCommandGroup(
new SpinShooter(shooter, ShooterState.SHOOT, true).andThen(new WaitCommand(2)),
new FeedActuate(intake, FeedMode.INTAKE).withTimeout(1)
).onlyIf(() -> !canShoot),
).onlyIf(() -> !canShoot).andThen(() -> canShoot = true),

new AutoAim(swerve, shooter, elevator, leds)
),
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ public class ShooterSubsystem extends SubsystemBase {

private final Debouncer _beamDebouncer = new Debouncer(0.3, DebounceType.kRising);

private double _shooterTrim = 1.55;
private double _shooterTrim = 3;

private boolean _holdNote = false;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ public class SwerveDriveSubsystem extends SubsystemBase {
/** A boolean for whether the swerve is field oriented or not. */
public boolean fieldOriented = false;

private double _swerveTrim = 0;
private double _swerveTrim = 8;

StructArrayPublisher<SwerveModuleState> publisher = NetworkTableInstance.getDefault()
.getStructArrayTopic("MyStates", SwerveModuleState.struct).publish();
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/utils/SwerveModule.java
Original file line number Diff line number Diff line change
Expand Up @@ -70,8 +70,8 @@ public SwerveModule(String name, int driveMotorId, int rotationMotorId, int enco

currentConfig.StatorCurrentLimit = 120;

currentConfig.SupplyCurrentLimitEnable = false;
currentConfig.StatorCurrentLimitEnable = false;
currentConfig.SupplyCurrentLimitEnable = true;
currentConfig.StatorCurrentLimitEnable = true;

_driveMotor.getConfigurator().apply(currentConfig);
}
Expand Down

0 comments on commit e7cc04d

Please sign in to comment.