Skip to content

Commit

Permalink
feat:small fix
Browse files Browse the repository at this point in the history
  • Loading branch information
ProgrammingSR committed Feb 27, 2024
1 parent 905328d commit 3bd14fc
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 71 deletions.
19 changes: 0 additions & 19 deletions src/main/deploy/pathplanner/paths/Bot_Dis_1.path
Original file line number Diff line number Diff line change
Expand Up @@ -81,25 +81,6 @@
"type": "sequential",
"data": {
"commands": [
{
"type": "parallel",
"data": {
"commands": [
{
"type": "wait",
"data": {
"waitTime": 0.5
}
},
{
"type": "named",
"data": {
"name": "align"
}
}
]
}
},
{
"type": "parallel",
"data": {
Expand Down
38 changes: 0 additions & 38 deletions src/main/deploy/pathplanner/paths/Shoot_Top1.path
Original file line number Diff line number Diff line change
Expand Up @@ -86,25 +86,6 @@
"type": "sequential",
"data": {
"commands": [
{
"type": "parallel",
"data": {
"commands": [
{
"type": "wait",
"data": {
"waitTime": 0.5
}
},
{
"type": "named",
"data": {
"name": "align"
}
}
]
}
},
{
"type": "parallel",
"data": {
Expand Down Expand Up @@ -226,25 +207,6 @@
"type": "sequential",
"data": {
"commands": [
{
"type": "parallel",
"data": {
"commands": [
{
"type": "wait",
"data": {
"waitTime": 0.5
}
},
{
"type": "named",
"data": {
"name": "align"
}
}
]
}
},
{
"type": "parallel",
"data": {
Expand Down
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,7 @@ public static final class ShooterConstants {
public static final int kTopShooterMotorPort = 35;
public static final int kBottomShooterMotorPort = 20;
public static final double kTimeShoot = 5;
public static final double kShooterMotorSpeed = 0;
}

public static final class VisionConstants {
Expand Down
32 changes: 18 additions & 14 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ public class RobotContainer {
private final ShooterSubsystem m_shooterSubsystem = new ShooterSubsystem();
public final IntakeSubsystem m_intakeSubsystem = new IntakeSubsystem();
private final SendableChooser<Command> autoChooser;

private boolean IntakeDropped = false;
private boolean lastAButton = false;

Expand All @@ -56,17 +56,19 @@ public class RobotContainer {
* The container for the robot. Contains subsystems, IO devices, and commands.
*/
public RobotContainer() {
//Registering Named Commands for autonpaths
//registerCommand is looking for XXXXXXCommand, so things may need to be renamed.
NamedCommands.registerCommand("shoot", new InstantCommand(() -> m_shooterSubsystem.shooterTimedRun(Constants.ShooterConstants.kTimeShoot, Constants.ShooterConstants.kSpinSpeedTrue)));
//NamedCommands.registerCommand("align", DriverSubsystem.autoAlign());
NamedCommands.registerCommand("intake", new InstantCommand(() -> m_intakeSubsystem.intakeTimedRun(Constants.IntakeConstants.kTimeIntake), m_intakeSubsystem));

//All paths automatically
// Registering Named Commands for autonpaths
// registerCommand is looking for XXXXXXCommand, so things may need to be
// renamed.
NamedCommands.registerCommand("shoot", new InstantCommand(() -> m_shooterSubsystem
.shooterTimedRun(Constants.ShooterConstants.kTimeShoot, Constants.ShooterConstants.kShooterMotorSpeed)));

NamedCommands.registerCommand("intake", new InstantCommand(
() -> m_intakeSubsystem.intakeTimedRun(Constants.IntakeConstants.kTimeIntake), m_intakeSubsystem));

// All paths automatically
autoChooser = AutoBuilder.buildAutoChooser();
SmartDashboard.putData("Auto Chooser", autoChooser);


AutoBuilder.configureHolonomic(m_robotDrive::getPose, m_robotDrive::resetOdometry,
m_robotDrive::getChassisSpeeds,
m_robotDrive::autonDrive,
Expand Down Expand Up @@ -121,8 +123,10 @@ private void configureBindings() {
.onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive));

// new JoystickButton(m_driverController, Button.kA.value).whileTrue(
// AutoBuilder.pathfindToPose(new Pose2d(2.8, 5.5, new Rotation2d()), new PathConstraints(
// DriveConstants.kMaxSpeedMetersPerSecond - 1, 5, DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5)));
// AutoBuilder.pathfindToPose(new Pose2d(2.8, 5.5, new Rotation2d()), new
// PathConstraints(
// DriveConstants.kMaxSpeedMetersPerSecond - 1, 5,
// DriveConstants.kMaxAngularSpeedRadiansPerSecond - 1, 5)));

new JoystickButton(m_operatorController, Button.kX.value)
.onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(0.75), m_shooterSubsystem))
Expand All @@ -136,16 +140,16 @@ private void configureBindings() {
}).whileTrue(new IntakeCommand(m_intakeSubsystem));
}


//adding auton Path options
// adding auton Path options

/**
* Use this to pass the autonomous command to the main {@link Robot} class.
*
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
PathPlannerPath path = PathPlannerPath.fromPathFile("New New Path");
Command follow = autoChooser.getSelected();
PathPlannerPath path = PathPlannerPath.fromPathFile(follow.getName());

var alliance = DriverStation.getAlliance();
PathPlannerPath autonPath = path;
Expand Down

0 comments on commit 3bd14fc

Please sign in to comment.