Skip to content

Commit

Permalink
Merge branch 'main' into 29-auto-align-to-tag-using-pathfinding
Browse files Browse the repository at this point in the history
  • Loading branch information
Vilok1 committed Mar 3, 2024
2 parents 6120e25 + e634a77 commit 92a83f8
Show file tree
Hide file tree
Showing 23 changed files with 381 additions and 83 deletions.
50 changes: 50 additions & 0 deletions src/main/deploy/pathplanner/autos/test hee hee.auto
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
{
"version": 1.0,
"startingPose": null,
"command": {
"type": "sequential",
"data": {
"commands": [
{
"type": "named",
"data": {
"name": "Cand-Sub"
}
},
{
"type": "deadline",
"data": {
"commands": [
{
"type": "path",
"data": {
"pathName": "Move Forward"
}
},
{
"type": "named",
"data": {
"name": "Collect"
}
}
]
}
},
{
"type": "path",
"data": {
"pathName": "Move Back"
}
},
{
"type": "named",
"data": {
"name": "Smart-Shoot"
}
}
]
}
},
"folder": null,
"choreoAuto": false
}
52 changes: 52 additions & 0 deletions src/main/deploy/pathplanner/paths/Move Back.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 2.65,
"y": 5.539225686154654
},
"prevControl": null,
"nextControl": {
"x": 1.6233924503512331,
"y": 5.531608026126181
},
"isLocked": false,
"linkedName": "C2"
},
{
"anchor": {
"x": 1.334102025955381,
"y": 5.567399971117918
},
"prevControl": {
"x": 2.483157024493337,
"y": 5.559782311089444
},
"nextControl": null,
"isLocked": false,
"linkedName": "SubwooferMiddle"
}
],
"rotationTargets": [],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0,
"rotation": 0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": 0,
"velocity": 0
},
"useDefaultConstraints": true
}
52 changes: 52 additions & 0 deletions src/main/deploy/pathplanner/paths/Move Forward.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
{
"version": 1.0,
"waypoints": [
{
"anchor": {
"x": 1.334102025955381,
"y": 5.567399971117918
},
"prevControl": null,
"nextControl": {
"x": 2.334102025955381,
"y": 5.567399971117918
},
"isLocked": false,
"linkedName": "SubwooferMiddle"
},
{
"anchor": {
"x": 2.65,
"y": 5.539225686154654
},
"prevControl": {
"x": 1.65,
"y": 5.539225686154654
},
"nextControl": null,
"isLocked": false,
"linkedName": "C2"
}
],
"rotationTargets": [],
"constraintZones": [],
"eventMarkers": [],
"globalConstraints": {
"maxVelocity": 3.0,
"maxAcceleration": 3.0,
"maxAngularVelocity": 540.0,
"maxAngularAcceleration": 720.0
},
"goalEndState": {
"velocity": 0.0,
"rotation": 0.0,
"rotateFast": false
},
"reversed": false,
"folder": null,
"previewStartingState": {
"rotation": 0.0,
"velocity": 0
},
"useDefaultConstraints": true
}
6 changes: 4 additions & 2 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -403,6 +403,7 @@ public class CollectorConstants { // TODO: get real
public static final double MOTOR_KA = 0;

public static final double COLLECTOR_SYSTEST_POWER = 0.25;
public static final double COLLECTOR_GRABANDGO_POWER = 0.75;
}

public class FlywheelConstants { // TODO: get real
Expand Down Expand Up @@ -499,6 +500,7 @@ public class ShooterConstants {
put(1.08d, 60d);
put(2.01d, 50d);
put(2.94d, 39d);
put(3.99d, 31d);
}
};

Expand All @@ -507,9 +509,9 @@ public class ShooterConstants {
{
// As distance get smaller RPM gets smaller
put(1.08d, 2000d);
put(2.01d, 2250d);
put(2.01d, 2000d);
put(2.94d, 2500d);

put(3.99d, 3250d);
}
};

Expand Down
15 changes: 9 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,7 @@
import frc.robot.command.Climb;
import frc.robot.command.CollisionDetection;
import frc.robot.command.Collect;
import frc.robot.command.CollectAndGo;
import frc.robot.subsystems.Limelights;
import frc.robot.subsystems.Swerve;
import frc.robot.subsystems.Climber;
Expand Down Expand Up @@ -138,9 +139,9 @@ protected void initializeNamedCommands() {
NamedCommands.registerCommand("led-Shoot",
leds.enableState(LED_STATES.SHOOTING).withTimeout(0.5));

NamedCommands.registerCommand("Cand-Sub",
NamedCommands.registerCommand("Cand-Sub",
new PointBlankShotAuton(flywheel, pivot, indexer)
.alongWith(leds.enableState(LED_STATES.SHOOTING).withTimeout(0.5)));
.alongWith(leds.enableState(LED_STATES.SHOOTING).withTimeout(1)));
NamedCommands.registerCommand("Cand-C1", new CandC1(flywheel, pivot, indexer));
NamedCommands.registerCommand("Cand-C2", new CandC2(flywheel, pivot, indexer));
NamedCommands.registerCommand("Cand-C3", new CandC3(flywheel, pivot, indexer));
Expand All @@ -156,6 +157,7 @@ protected void initializeNamedCommands() {
.alongWith(leds.enableState(LED_STATES.COLLECTING).withTimeout(1)));
NamedCommands.registerCommand("Index-Up", new Index(() -> IndexerConstants.INDEXER_DEFAULT_POWER, indexer));
NamedCommands.registerCommand("PathFind", new MoveToPose(AutonomousConstants.TARGET_POSE, drivetrain));
NamedCommands.registerCommand("Collect-And-Go", new CollectAndGo(collector));

// make sure named commands are initialized before autobuilder!
autoChooser = AutoBuilder.buildAutoChooser();
Expand Down Expand Up @@ -208,13 +210,13 @@ protected void configureButtonBindings() {
// Test auto align
/* copilot */
new Trigger(coPilot::getBButton)
.whileTrue(new SmartCollect(() -> 0.50, () -> 0.60, collector, indexer, pivot)); // TODO: find correct button/trigger
.whileTrue(new InstantCommand(() -> flywheel.stop(), flywheel)
.andThen(new SmartCollect(() -> 0.50, () -> 0.60, collector, indexer, pivot))); // TODO: find correct button/trigger

// cand shots for the robot
new Trigger(coPilot::getAButton).whileTrue(new AmpShot(flywheel, pivot));
// new Trigger(coPilot::getXButton).whileTrue(new PointBlankShot(flywheel, pivot));
new Trigger(coPilot::getXButton).whileTrue(new PointBlankShot(flywheel, pivot));
// new Trigger(coPilot::getYButton).whileTrue(new PodiumShot(flywheel, pivot));
new Trigger(coPilot::getXButton).whileTrue(new Tune(flywheel, pivot));
new Trigger(coPilot::getYButton).whileTrue(new SourceCollect(flywheel, pivot));

// new Trigger(coPilot::getBButton).whileTrue(new Climb(climber, // TODO need new button start? Back?
Expand Down Expand Up @@ -264,7 +266,8 @@ protected void configureDefaultCommands() {

/* copilot */
collector.setDefaultCommand(
new Collect(() -> MathUtil.applyDeadband((coPilot.getRightTriggerAxis() - coPilot.getLeftTriggerAxis()), ControllerConstants.DEADBAND), collector, indexer));
new Collect(() -> MathUtil.applyDeadband((coPilot.getRightTriggerAxis() - coPilot.getLeftTriggerAxis()), ControllerConstants.DEADBAND), collector));

// climber.setDefaultCommand(new ManualClimb(() -> coPilot.getLeftY(),() ->
// coPilot.getRightY(), climber));
}
Expand Down
13 changes: 2 additions & 11 deletions src/main/java/frc/robot/command/Collect.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,26 +4,22 @@

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Collector;
import frc.robot.subsystems.Indexer;
import frc.thunder.shuffleboard.LightningShuffleboard;

public class Collect extends Command {

// Declares collector
private DoubleSupplier powerSupplier;
private Collector collector;
private Indexer indexer;

/**
* Creates a new Collect.
* @param powerSupplier DoubleSupplier for power of motor (-1 to 1)
* @param collector subsystem
* @param indexer subsystem
*/
public Collect(DoubleSupplier powerSupplier, Collector collector, Indexer indexer) {
this.powerSupplier = powerSupplier;
public Collect(DoubleSupplier powerSupplier, Collector collector) {
this.collector = collector;
this.indexer = indexer;
this.powerSupplier = powerSupplier;

addRequirements(collector);
}
Expand All @@ -37,11 +33,6 @@ public void initialize() {
@Override
public void execute() {
collector.setPower(powerSupplier.getAsDouble());
if (powerSupplier.getAsDouble() > 0d) {
indexer.setPower(1d);
} else {
indexer.stop();
}
}

@Override
Expand Down
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/command/CollectAndGo.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot.command;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.Collector;
import frc.robot.Constants.CollectorConstants;

public class CollectAndGo extends Command {

private final Collector collector;

/** Creates a new CollectAndGo.
* @param collector subsystem
*/
public CollectAndGo(Collector collector) {
this.collector = collector;
addRequirements(collector);
}

@Override
public void initialize() {
collector.setPower(CollectorConstants.COLLECTOR_GRABANDGO_POWER);
}

@Override
public void execute() {
collector.setPower(CollectorConstants.COLLECTOR_GRABANDGO_POWER);
}

@Override
public void end(boolean interrupted) {
collector.stop();
}

@Override
public boolean isFinished() {
return collector.getEntryBeamBreakState();
}
}
4 changes: 3 additions & 1 deletion src/main/java/frc/robot/command/SmartCollect.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,9 @@ public SmartCollect(DoubleSupplier collectorPower, DoubleSupplier indexerPower,
}

@Override
public void initialize() {}
public void initialize() {

}

@Override
public void execute() {
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/command/shoot/AmpShot.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,13 +8,13 @@

public class AmpShot extends Command {

private Pivot pivot;
private Flywheel flywheel;
private final Flywheel flywheel;
private final Pivot pivot;

/**
* Creates a new AmpShot
* @param pivot subsystem
* @param flywheel subsystem
* @param pivot subsystem
*/
public AmpShot(Flywheel flywheel, Pivot pivot) {
this.flywheel = flywheel;
Expand All @@ -32,9 +32,9 @@ public void initialize() {

@Override
public void execute() {
pivot.setTargetAngle(CandConstants.AMP_ANGLE + pivot.getBias());
flywheel.setTopMoterRPM(CandConstants.AMP_TOP_RPM + flywheel.getBias());
flywheel.setBottomMoterRPM(CandConstants.AMP_BOTTOM_RPM + flywheel.getBias());
pivot.setTargetAngle(CandConstants.AMP_ANGLE + pivot.getBias());
}

@Override
Expand Down
Loading

0 comments on commit 92a83f8

Please sign in to comment.