Skip to content
This repository was archived by the owner on Nov 29, 2024. It is now read-only.

Commit

Permalink
AHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHHH mark 2 electric booglaoo
Browse files Browse the repository at this point in the history
  • Loading branch information
Clementine4089 committed Mar 25, 2023
1 parent d473ede commit dde36fd
Show file tree
Hide file tree
Showing 19 changed files with 354 additions and 118 deletions.
74 changes: 74 additions & 0 deletions src/main/deploy/pathplanner/Right Path Total.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,74 @@
{
"waypoints": [
{
"anchorPoint": {
"x": 1.946448286619825,
"y": 1.6009641149096854
},
"prevControl": null,
"nextControl": {
"x": 2.3009474834926844,
"y": -0.11435457963640693
},
"holonomicAngle": 0.0,
"isReversal": false,
"velOverride": null,
"isLocked": false,
"isStopPoint": false,
"stopEvent": {
"names": [],
"executionBehavior": "parallel",
"waitBehavior": "none",
"waitTime": 0
}
},
{
"anchorPoint": {
"x": 6.56487514898107,
"y": 0.9249526191360088
},
"prevControl": {
"x": 5.688097145425064,
"y": 1.0020320040640094
},
"nextControl": {
"x": 7.441653152537076,
"y": 0.8478732342080082
},
"holonomicAngle": 0.0,
"isReversal": false,
"velOverride": null,
"isLocked": false,
"isStopPoint": false,
"stopEvent": {
"names": [],
"executionBehavior": "parallel",
"waitBehavior": "none",
"waitTime": 0
}
},
{
"anchorPoint": {
"x": 1.96,
"y": 0.41
},
"prevControl": {
"x": 1.9407301537679995,
"y": 0.4774444618120008
},
"nextControl": null,
"holonomicAngle": 0,
"isReversal": false,
"velOverride": null,
"isLocked": false,
"isStopPoint": false,
"stopEvent": {
"names": [],
"executionBehavior": "parallel",
"waitBehavior": "none",
"waitTime": 0
}
}
],
"markers": []
}
49 changes: 49 additions & 0 deletions src/main/deploy/pathplanner/moveOut.path
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
{
"waypoints": [
{
"anchorPoint": {
"x": 1.9304771301850319,
"y": 3.285508782556027
},
"prevControl": null,
"nextControl": {
"x": 2.9304771301850314,
"y": 3.285508782556027
},
"holonomicAngle": 0,
"isReversal": false,
"velOverride": null,
"isLocked": false,
"isStopPoint": false,
"stopEvent": {
"names": [],
"executionBehavior": "parallel",
"waitBehavior": "none",
"waitTime": 0
}
},
{
"anchorPoint": {
"x": 6.5663733039306305,
"y": 3.384895557237619
},
"prevControl": {
"x": 5.880245826112194,
"y": 3.355099094620442
},
"nextControl": null,
"holonomicAngle": 0,
"isReversal": false,
"velOverride": null,
"isLocked": false,
"isStopPoint": false,
"stopEvent": {
"names": [],
"executionBehavior": "parallel",
"waitBehavior": "none",
"waitTime": 0
}
}
],
"markers": []
}
16 changes: 10 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,12 +12,13 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import frc.robot.subsystems.RotatorSubsystem;
import frc.robot.subsystems.CandleSubsystem;
import frc.robot.subsystems.CrocodileSubsystem;
import frc.robot.commands.*;
import frc.robot.commands.Autos.PreloadParkCenter;
import frc.robot.commands.Autos.PreloadPlusOneLeft;
import frc.robot.commands.Autos.PreloadPlusOneRight;
import frc.robot.commands.Autos.EXIT_COMMUNITY;
import frc.robot.commands.Autos.DO_NOTHING;
import frc.robot.commands.DefaultCommands.CrocodileDefaultCommand;
import frc.robot.commands.DefaultCommands.RotatorDefaultCommand;
import frc.robot.commands.DefaultCommands.TeleopDrivebaseDefaultCommand;
Expand Down Expand Up @@ -67,7 +68,7 @@ public class RobotContainer {
private final RotatorSubsystem rotator;
private final CrocodileSubsystem endEffector;
private final TelescopeSubsystem telescope;
private final CandleSubsystem candle;
//private final CandleSubsystem candle;

private UsbCamera camera = CameraServer.startAutomaticCapture();
private SendableChooser<Command> autoChooser = new SendableChooser<>();
Expand All @@ -84,7 +85,7 @@ public RobotContainer() {
SmartDashboard.putData("Rotator", rotator);
endEffector = new CrocodileSubsystem();
SmartDashboard.putData("Intake", endEffector);
candle = new CandleSubsystem();
//candle = new CandleSubsystem();

camera.setResolution(160, 120);
camera.setFPS(30);
Expand Down Expand Up @@ -118,6 +119,8 @@ public RobotContainer() {
autoChooser.setDefaultOption("CENTER Preload Park", new PreloadParkCenter(swerve, endEffector, rotator, telescope));
autoChooser.addOption("RIGHT Preload + 1", new PreloadPlusOneRight(swerve, endEffector, rotator, telescope));
autoChooser.addOption("LEFT Preload + 1", new PreloadPlusOneLeft(swerve, endEffector, rotator, telescope));
autoChooser.addOption("EXIT COMMUNITY", new EXIT_COMMUNITY(swerve, endEffector, rotator, telescope));
autoChooser.addOption("DO NOTHING", new DO_NOTHING(swerve, endEffector, rotator, telescope));
SmartDashboard.putData("Selected Autonomous", autoChooser);

// Configure the button bindings
Expand Down Expand Up @@ -152,16 +155,17 @@ private void configureButtonBindings() {
mechController.povLeft().onTrue(new InstantCommand(() -> telescope.resetEncoder()));
mechController.button(8).onTrue(new InstantCommand(() -> {
endEffector.setGamePiece(GamePiece.CONE);
candle.cone();
//candle.cone();
}, endEffector));
mechController.button(7).onTrue(new InstantCommand(() -> {
endEffector.setGamePiece(GamePiece.CUBE);
candle.cube();
//candle.cube();
}, endEffector));
mechController.povDown()
.onTrue(new SubstationPickupPresetSequence(telescope, rotator, endEffector, driverController.y(),
() -> endEffector.getGamePiece()));
driverController.y().onTrue(new AutoIntakeCommand(endEffector, 0.5, driverController.y()));
// driverController.y().onTrue(new AutoIntakeCommand(endEffector, 0.5, driverController.y()));
driverController.leftBumper().onTrue(new AutoIntakeCommand(endEffector, 0.75, driverController.leftBumper()));
}

public void teleopInit() {
Expand Down
65 changes: 65 additions & 0 deletions src/main/java/frc/robot/commands/Autos/DO_NOTHING.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,65 @@
// 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.commands.Autos;

import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.SharedConstants;
import frc.robot.RobotMap.Crocodile;
import frc.robot.commands.AutoIntakeCommand;
import frc.robot.commands.ResetTelescope;
import frc.robot.commands.RotatorToPosition;
import frc.robot.commands.SwerveTrajectoryFollowCommand;
import frc.robot.commands.TelescopeToPosition;
import frc.robot.commands.Presets.HighPresetSequence;
import frc.robot.commands.Presets.PickupPresetSequence;
import frc.robot.commands.Presets.StowPresetSequence;
import frc.robot.subsystems.CrocodileSubsystem;
import frc.robot.subsystems.RotatorSubsystem;
import frc.robot.subsystems.TelescopeSubsystem;
import frc.robot.subsystems.CrocodileSubsystem.GamePiece;
import frc.robot.subsystems.Swerve.DrivebaseSubsystem;

public class DO_NOTHING extends SequentialCommandGroup {

public DO_NOTHING(DrivebaseSubsystem driveBase, CrocodileSubsystem croc, RotatorSubsystem rotator,
TelescopeSubsystem telescope) {
addCommands(
new InstantCommand()

/*
* start
* rotate telescope to scoring position
* extend telescope to top position
* move wrist to 90 degrees
* drop cone using chomper
* move wrist back up to original position
* retract arm
* rotate arm to standby/pickup position
* move forward to the cone
* extend arm out
* move wrist down to grabbing position
* move forward some more while wrist is sucking up cone to pick it up
* retract arm in
* move back to starting position
* more over to the left/right in line up with poles
* flip arm over
* extend arm to top position
* move wrist to 90 degrees
* drop cone using chomper
* move wrist back up to original position
* retract arm back in
* rotate arm to standby/pickup position
* end
*/

);
// grabs any requirements needed for the drivebase from other running commands.
addRequirements(driveBase);
}
}
68 changes: 68 additions & 0 deletions src/main/java/frc/robot/commands/Autos/EXIT_COMMUNITY.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
// 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.commands.Autos;

import edu.wpi.first.math.trajectory.TrajectoryConfig;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.SharedConstants;
import frc.robot.RobotMap.Crocodile;
import frc.robot.commands.AutoIntakeCommand;
import frc.robot.commands.ResetTelescope;
import frc.robot.commands.RotatorToPosition;
import frc.robot.commands.SwerveTrajectoryFollowCommand;
import frc.robot.commands.TelescopeToPosition;
import frc.robot.commands.Presets.HighPresetSequence;
import frc.robot.commands.Presets.PickupPresetSequence;
import frc.robot.commands.Presets.StowPresetSequence;
import frc.robot.subsystems.CrocodileSubsystem;
import frc.robot.subsystems.RotatorSubsystem;
import frc.robot.subsystems.TelescopeSubsystem;
import frc.robot.subsystems.CrocodileSubsystem.GamePiece;
import frc.robot.subsystems.Swerve.DrivebaseSubsystem;

public class EXIT_COMMUNITY extends SequentialCommandGroup {
private final TrajectoryConfig defaultConfig;

public EXIT_COMMUNITY(DrivebaseSubsystem driveBase, CrocodileSubsystem croc, RotatorSubsystem rotator,
TelescopeSubsystem telescope) {
this.defaultConfig = new TrajectoryConfig(SharedConstants.AutoConstants.k_MAX_SPEED_MPS,
SharedConstants.AutoConstants.k_MAX_ACCEL_MPS_SQUARED);
addCommands(
new SwerveTrajectoryFollowCommand(driveBase, "moveOut", defaultConfig, true)

/*
* start
* rotate telescope to scoring position
* extend telescope to top position
* move wrist to 90 degrees
* drop cone using chomper
* move wrist back up to original position
* retract arm
* rotate arm to standby/pickup position
* move forward to the cone
* extend arm out
* move wrist down to grabbing position
* move forward some more while wrist is sucking up cone to pick it up
* retract arm in
* move back to starting position
* more over to the left/right in line up with poles
* flip arm over
* extend arm to top position
* move wrist to 90 degrees
* drop cone using chomper
* move wrist back up to original position
* retract arm back in
* rotate arm to standby/pickup position
* end
*/

);
// grabs any requirements needed for the drivebase from other running commands.
addRequirements(driveBase);
}
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/Autos/PreloadParkCenter.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
import frc.robot.commands.SwerveTrajectoryFollowCommand;
import frc.robot.commands.TelescopeToPosition;
import frc.robot.commands.Presets.HighPresetSequence;
import frc.robot.commands.Presets.MidPresetSequence;
import frc.robot.commands.Presets.StowPresetSequence;
import frc.robot.subsystems.CrocodileSubsystem;
import frc.robot.subsystems.RotatorSubsystem;
Expand All @@ -43,13 +44,12 @@ public PreloadParkCenter(DrivebaseSubsystem driveBase, CrocodileSubsystem croc,
this.defaultConfig = new TrajectoryConfig(SharedConstants.AutoConstants.k_MAX_SPEED_MPS,
SharedConstants.AutoConstants.k_MAX_ACCEL_MPS_SQUARED);
addCommands(
new HighPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE),
new HighPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE),
new MidPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE).withTimeout(2.5),
new InstantCommand(() -> croc.setIntakeSpeed(-1)),
new WaitCommand(0.25),
new InstantCommand(() -> croc.setIntakeSpeed(0)),
new ParallelCommandGroup(
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE).withTimeout(3),
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE).withTimeout(3).withTimeout(2.5),
new SwerveTrajectoryFollowCommand(driveBase, "preloadParkCenter", defaultConfig, true)),
new LevelRobot(driveBase)
/*
Expand Down
11 changes: 7 additions & 4 deletions src/main/java/frc/robot/commands/Autos/PreloadPlusOneLeft.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,13 @@
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.SharedConstants;
import frc.robot.RobotMap.Crocodile;
import frc.robot.commands.AutoIntakeCommand;
import frc.robot.commands.ResetTelescope;
import frc.robot.commands.RotatorToPosition;
import frc.robot.commands.SwerveTrajectoryFollowCommand;
import frc.robot.commands.TelescopeToPosition;
import frc.robot.commands.Presets.HighPresetSequence;
import frc.robot.commands.Presets.MidPresetSequence;
import frc.robot.commands.Presets.PickupPresetSequence;
import frc.robot.commands.Presets.StowPresetSequence;
import frc.robot.subsystems.CrocodileSubsystem;
Expand Down Expand Up @@ -43,19 +45,20 @@ public PreloadPlusOneLeft(DrivebaseSubsystem driveBase, CrocodileSubsystem croc,
this.defaultConfig = new TrajectoryConfig(SharedConstants.AutoConstants.k_MAX_SPEED_MPS,
SharedConstants.AutoConstants.k_MAX_ACCEL_MPS_SQUARED);
addCommands(
new HighPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE),
new MidPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE).withTimeout(2.5),
new InstantCommand(() -> croc.setIntakeSpeed(-1)),
new WaitCommand(0.25),
new InstantCommand(() -> croc.setIntakeSpeed(0)),
new ParallelCommandGroup(
new PickupPresetSequence(telescope, rotator, croc, null).withTimeout(3),
new SwerveTrajectoryFollowCommand(driveBase, "preloadPlusOneLeft1", defaultConfig, true)),
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE),
new AutoIntakeCommand(croc, 1, GamePiece.CONE),
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE).withTimeout(2.5),
new SwerveTrajectoryFollowCommand(driveBase, "preloadPlusOneLeft2", defaultConfig),
new HighPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE),
new MidPresetSequence(telescope, rotator, croc, null, () -> GamePiece.CONE).withTimeout(2.5),
new InstantCommand(() -> croc.setIntakeSpeed(-1)),
new WaitCommand(0.25),
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE)
new StowPresetSequence(telescope, rotator, croc, () -> 0, () -> GamePiece.CONE).withTimeout(2.5)

/*
* start
Expand Down
Loading

0 comments on commit dde36fd

Please sign in to comment.