after merge
This commit is contained in:
@@ -7,7 +7,7 @@ import frc.robot.subsystems.Shooter;
|
||||
public class AmpHandoff extends ParallelCommandGroup{
|
||||
|
||||
AmpHandoff(Indexer indexer, Shooter shooter){
|
||||
addCommands(indexer.shootNote(null), shooter.ampHandoff());
|
||||
addCommands(indexer.shootNote(() -> 1), shooter.ampHandoff());
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -21,6 +21,7 @@ import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.button.Trigger;
|
||||
@@ -89,7 +90,8 @@ public class RobotContainer {
|
||||
|
||||
climber = new Climber(shooter::getShooterAngle);
|
||||
|
||||
|
||||
NamedCommands.registerCommand("Charge Shooter", shooter.angleSpeedsSetpoints(() -> ShooterConstants.kShooterLoadAngle, 1.0, 1.0));
|
||||
NamedCommands.registerCommand("Speake Note Shot", Commands.parallel(shooter.angleSpeedsSetpoints(() -> ShooterConstants.kShooterLoadAngle, 1.0, 1.0), indexer.shootNote(() -> 1.0)));
|
||||
|
||||
// An example Named Command, doesn't need to remain once we start actually adding real things
|
||||
// ALL Named Commands need to be defined AFTER subsystem initialization and BEFORE auto/controller configuration
|
||||
|
||||
@@ -47,5 +47,5 @@ public final class DrivetrainConstants {
|
||||
|
||||
public static final boolean kGyroReversed = true;
|
||||
|
||||
public static final double kRobotStartOffset = 0.0;
|
||||
public static final double kRobotStartOffset = 0;
|
||||
}
|
||||
|
||||
@@ -13,8 +13,8 @@ public class IntakeConstants {
|
||||
public static final double kDIntake = 0;
|
||||
|
||||
public static final double kSFeedForward = 0;
|
||||
public static final double kGFeedForward = 0;
|
||||
public static final double kVFeedForward = 0;
|
||||
public static final double kGFeedForward = 1.11;
|
||||
public static final double kVFeedForward = 0.73;
|
||||
|
||||
public static final double kStartingAngle = Math.toRadians(105.0);
|
||||
public static final double kUpAngle = Math.toRadians(90.0);
|
||||
|
||||
@@ -22,8 +22,8 @@ public class ShooterConstants {
|
||||
public static final double kPivotConversion = 1/(40.0*(28.0/15.0));
|
||||
|
||||
public static final double kSShooterPivotFF = 0.0;
|
||||
public static final double kGShooterPivotFF = 0.0;
|
||||
public static final double kVShooterPivotFF = 0.0;
|
||||
public static final double kGShooterPivotFF = 0.33;
|
||||
public static final double kVShooterPivotFF = 1.44;
|
||||
|
||||
public static final double kMaxPivotSpeed = 0.0;
|
||||
public static final double kMaxPivotAcceleration = 0.0;
|
||||
|
||||
@@ -2,7 +2,6 @@ package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.revrobotics.CANSparkBase.IdleMode;
|
||||
|
||||
Reference in New Issue
Block a user