Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Auto speed depending on vision assistance toggle #310

Open
wants to merge 3 commits into
base: main
Choose a base branch
from
Open
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
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import competition.subsystems.drive.commands.DriveToCentralSubwooferCommand;
import competition.subsystems.drive.commands.DriveToListOfPointsCommand;
import competition.subsystems.pose.PoseSubsystem;
import competition.subsystems.vision.VisionSubsystem;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
Expand All @@ -29,7 +30,7 @@ public SubwooferShotFromMidShootThenShootNearestThree(AutonomousCommandSelector
Provider<DriveToGivenNoteAndCollectCommandGroup> driveToGivenNoteAndCollectCommandGroupProvider,
Provider<FireFromSubwooferCommandGroup> fireFromSubwooferCommandGroup,
Provider<DriveToCentralSubwooferCommand> driveToCentralSubwooferCommandProvider,
PoseSubsystem pose, DriveSubsystem drive) {
PoseSubsystem pose, DriveSubsystem drive, VisionSubsystem vision) {
this.autoSelector = autoSelector;

// Force our location
Expand All @@ -50,6 +51,7 @@ public SubwooferShotFromMidShootThenShootNearestThree(AutonomousCommandSelector
})
);
var driveToMiddleSpikeNoteAndCollect = driveToGivenNoteAndCollectCommandGroupProvider.get();
driveToMiddleSpikeNoteAndCollect.setMaximumSpeedOverride(vision.getSpeedForAuto());
this.addCommands(driveToMiddleSpikeNoteAndCollect.withTimeout(interstageTimeout));

// Drive back to subwoofer
Expand All @@ -68,6 +70,7 @@ public SubwooferShotFromMidShootThenShootNearestThree(AutonomousCommandSelector
})
);
var driveToTopSpikeNoteAndCollect = driveToGivenNoteAndCollectCommandGroupProvider.get();
driveToTopSpikeNoteAndCollect.setMaximumSpeedOverride(vision.getSpeedForAuto());
this.addCommands(driveToTopSpikeNoteAndCollect.withTimeout(interstageTimeout));

// Drive back to subwoofer
Expand All @@ -94,6 +97,7 @@ public SubwooferShotFromMidShootThenShootNearestThree(AutonomousCommandSelector

// Now, go get the bottom spike note
var driveToBottomSpikeNoteAndCollect = driveToGivenNoteAndCollectCommandGroupProvider.get();
driveToBottomSpikeNoteAndCollect.setMaximumSpeedOverride(vision.getSpeedForAuto());
this.addCommands(driveToBottomSpikeNoteAndCollect.withTimeout(interstageTimeout));

// Drive back to subwoofer
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,7 @@ public class DriveSubsystem extends BaseSwerveDriveSubsystem implements DataFram
private Translation2d specialPointAtPositionTarget = new Translation2d();
private final DoubleProperty suggestedAutonomousMaximumSpeed;
private final DoubleProperty suggestedAutonomousExtremeSpeed;
private final DoubleProperty suggestedAutonomousSpeedIfNotVisionAssisted;
private final PIDManager aggressiveGoalHeadingPidManager;

@Inject
Expand All @@ -54,6 +55,8 @@ public DriveSubsystem(PIDManagerFactory pidFactory, PropertyFactory pf,
pf.createPersistentProperty("Suggested Autonomous Maximum Speed", 3.0);
suggestedAutonomousExtremeSpeed =
pf.createPersistentProperty("Suggested Autonomous EXTREME Speed", 5.0);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

⭐ ⭐ ⭐ there are actually 2 auto speeds (normal and extreme), and I think your override should impact both of them, so we'll want another property for the no vision extreme speed?

suggestedAutonomousSpeedIfNotVisionAssisted =
pf.createPersistentProperty("Suggested Autonomous NO VISION Speed", 1.5);

aggressiveGoalHeadingPidManager = aggressiveGoalHeadingPidFactory.create(
this.getPrefix() + "AggressiveGoalHeadingPID",
Expand All @@ -77,6 +80,9 @@ public double getSuggestedAutonomousMaximumSpeed() {
}

public double getSuggestedAutonomousExtremeSpeed() { return suggestedAutonomousExtremeSpeed.get(); }
public double getSuggestedAutonomousNoAutoSpeed() {
return suggestedAutonomousSpeedIfNotVisionAssisted.get();
}

@Override
protected PIDDefaults getPositionalPIDDefaults() {
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
package competition.subsystems.drive.commands;

import competition.subsystems.collector.CollectorSubsystem;
import competition.subsystems.drive.DriveSubsystem;
import competition.subsystems.oracle.DynamicOracle;
import competition.subsystems.pose.PoseSubsystem;
import competition.subsystems.vision.NoteSeekLogic;
import competition.subsystems.vision.VisionSubsystem;
import xbot.common.properties.PropertyFactory;
import xbot.common.subsystems.drive.control_logic.HeadingModule;

import javax.inject.Inject;

public class DriveToGivenNoteWithBearingVisionAndVisionAssistanceConsiderationCommand extends DriveToGivenNoteWithBearingVisionCommand{

VisionSubsystem vision;

@Inject
DriveToGivenNoteWithBearingVisionAndVisionAssistanceConsiderationCommand(
PoseSubsystem pose, DriveSubsystem drive, DynamicOracle oracle,
PropertyFactory pf, HeadingModule.HeadingModuleFactory headingModuleFactory,
VisionSubsystem vision, CollectorSubsystem collector, NoteSeekLogic noteSeekLogic) {
super(pose, drive, oracle, pf, headingModuleFactory, vision, collector, noteSeekLogic);
this.vision = vision;
}

@Override
public void execute() {
super.setMaximumSpeedOverride(vision.getSpeedForAuto());
super.execute();
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package competition.subsystems.vision;

import competition.electrical_contract.CompetitionContract;
import competition.subsystems.drive.DriveSubsystem;
import competition.subsystems.pose.PoseSubsystem;
import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.apriltag.AprilTagFields;
Expand Down Expand Up @@ -39,6 +40,7 @@
@Singleton
public class VisionSubsystem extends BaseSubsystem implements DataFrameRefreshable {

DriveSubsystem drive;
final RobotAssertionManager assertionManager;
final BooleanProperty isInverted;
final DoubleProperty yawOffset;
Expand Down Expand Up @@ -73,11 +75,14 @@ public class VisionSubsystem extends BaseSubsystem implements DataFrameRefreshab
public final double terminalNotePitch = 0.0;

public final DoubleProperty terminalNoteYawRange;
BooleanProperty usingVisionForAuto;


@Inject
public VisionSubsystem(PropertyFactory pf, XCameraElectricalContract electricalContract, RobotAssertionManager assertionManager) {
public VisionSubsystem(PropertyFactory pf, XCameraElectricalContract electricalContract, RobotAssertionManager assertionManager,
DriveSubsystem drive) {
this.assertionManager = assertionManager;
this.drive = drive;

pf.setPrefix(this);
isInverted = pf.createPersistentProperty("Yaw inverted", true);
Expand All @@ -89,6 +94,8 @@ public VisionSubsystem(PropertyFactory pf, XCameraElectricalContract electricalC
minNoteConfidence = pf.createPersistentProperty("Min note confidence", 0.8);
minNoteArea = pf.createPersistentProperty("Minimum note area", 0.5);

usingVisionForAuto = pf.createPersistentProperty("Using vision for auto", true);

terminalNoteYawRange = pf.createPersistentProperty("Terminal Note Yaw Range", 5.0);

bestRangeFromStaticNoteToSearchForNote = pf.createPersistentProperty("BestRangeFromStaticNoteToSearchForNote", 1.2);
Expand Down Expand Up @@ -487,4 +494,12 @@ else if (allCameras.stream().allMatch(state -> !state.isCameraWorking())) {
// If some of the cameras are working, return 2
return 2;
}

public double getSpeedForAuto() {
if (usingVisionForAuto.get()) {
return drive.getSuggestedAutonomousExtremeSpeed();
} else {
return drive.getSuggestedAutonomousNoAutoSpeed();
}
}
}