-
Notifications
You must be signed in to change notification settings - Fork 0
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
Shooter commands #8
base: testing
Are you sure you want to change the base?
Changes from 94 commits
c16f84b
81d7450
64d77ea
8ba0ee3
92f22cb
d0a3fa7
564d95e
dee813c
4466882
106a003
54c8acb
6b5a38a
b3ff845
d7c2cda
8185448
3a82edb
318cd2e
1b61489
f2f24ba
fd35775
b098fdf
2e68936
9727dca
f750125
5fbf836
36f80d8
5d4a445
65f1d1f
b2c3342
8a306f5
895f2c3
b7ac2bc
eafdff7
04a80f1
f39b159
0d5bedd
b956594
767e994
034fabb
5dc651d
8e223de
85e69d0
66c8cc9
6dadfb2
d4458bc
17df07d
d4a2bf9
d26112e
ec6fa20
b09f3dd
76515c2
9ca9c14
f1399b4
57a0820
dd60f57
a3a9b4b
71f93ee
8d55876
020561a
42d1161
7dd93c7
82a00dd
765431d
8334927
93b6615
eef31be
7afe928
d51fca0
0f89bc4
1e2d750
f272320
f451114
8855352
85e7705
636a8e5
7b083bf
d306139
6ac756f
740df35
badd0e6
1c18c16
37b0ff5
d069e3d
9c3fcac
04b8966
3db1887
8292487
de56b9c
0b07aa9
bb2da69
ce9f776
35c75cd
3d03fe8
4691673
f6d6c5f
069a10b
0aaaa87
547d628
a8e585f
bfaedda
b40ec57
7a80366
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,7 +1,20 @@ | ||
package org.usfirst.frc4904.robot; | ||
|
||
import org.usfirst.frc4904.robot.subsystems.Flywheel; | ||
import org.usfirst.frc4904.robot.subsystems.Indexer; | ||
import org.usfirst.frc4904.robot.subsystems.Intake; | ||
import org.usfirst.frc4904.robot.subsystems.Shooter; | ||
import org.usfirst.frc4904.standard.custom.PCMPort; | ||
import org.usfirst.frc4904.standard.custom.controllers.CustomJoystick; | ||
import org.usfirst.frc4904.standard.custom.controllers.CustomXbox; | ||
import org.usfirst.frc4904.standard.custom.motioncontrollers.CANTalonFX; | ||
import org.usfirst.frc4904.standard.custom.motioncontrollers.CANTalonSRX; | ||
import org.usfirst.frc4904.standard.custom.motioncontrollers.CustomPIDController; | ||
import org.usfirst.frc4904.standard.custom.sensors.CANTalonEncoder; | ||
import org.usfirst.frc4904.standard.custom.sensors.CustomDigitalLimitSwitch; | ||
import org.usfirst.frc4904.standard.subsystems.SolenoidSubsystem; | ||
import org.usfirst.frc4904.standard.subsystems.motor.Motor; | ||
import org.usfirst.frc4904.robot.subsystems.Hood; | ||
|
||
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics; | ||
|
||
|
@@ -13,36 +26,107 @@ public static class HumanInput { | |
} | ||
|
||
public static class CANMotor { | ||
// Intake | ||
public static final int INTAKE_ROLLER_MOTOR = 10; | ||
public static final int INTAKE_FUNNEL_MOTOR = 5; | ||
// Indexer | ||
public static final int LIFT_BELT_MOTOR = 6; | ||
// Flywheel | ||
public static final int FLYWHEEL_MOTOR_A = 2; | ||
public static final int FLYWHEEL_MOTOR_B = 1; | ||
// Shooter | ||
public static final int RUN_UP_BELT_MOTOR = 8; | ||
} | ||
|
||
public static class PWM { | ||
public static class PWM { // TODO: CHANGE CONSTS | ||
} | ||
|
||
public static class CAN { | ||
public static class CAN { // TODO: CHANGE CONSTS | ||
public static final int HOOD_MOTOR = -1; | ||
public static final int HOOD_ENCODER = -1; | ||
} | ||
|
||
public static class Pneumatics { | ||
public static class Pneumatics { // TODO: CHANGE CONSTS | ||
public static final PCMPort INTAKE_SOLENOID = new PCMPort(0, -1, -1); | ||
public static final PCMPort FLIPPER_SOLENOID = new PCMPort(0, -1, -1); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. We probably aren't using a flipper. |
||
public static final PCMPort SHOOTER_AIM_SOLENOID = new PCMPort(0, -1, -1); | ||
} | ||
|
||
public static class Digital { | ||
public static class Digital { // TODO: CHANGE CONSTS | ||
public static final int INDEXER_LIMIT_SWITCH = -1; | ||
public static final int HOOD_LOWER_LIMIT_SWITCH = -1; | ||
public static final int HOOD_UPPER_LIMIT_SWITCH = -1; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It's currently one limit switch, with two different magnets. |
||
} | ||
} | ||
|
||
public static class Metrics { | ||
public static class Chassis { | ||
public static final double TICKS_PER_REVOLUTION = -1; // TODO: CHANGE CONSTS | ||
public static final double DIAMETER_INCHES = -1; | ||
public static final double CIRCUMFERENCE_INCHES = Metrics.Chassis.DIAMETER_INCHES * Math.PI; | ||
public static final double DIAMETER_METERS = -1; | ||
public static final double CIRCUMFERENCE_METERS = Metrics.Chassis.DIAMETER_METERS * Math.PI; | ||
public static final double TICKS_PER_INCH = Metrics.Chassis.TICKS_PER_REVOLUTION | ||
/ Metrics.Chassis.CIRCUMFERENCE_INCHES; | ||
/ Metrics.Chassis.CIRCUMFERENCE_METERS; | ||
public static final double DISTANCE_FRONT_BACK = -1; | ||
public static final double DISTANCE_SIDE_SIDE = -1; | ||
public static final double INCHES_PER_TICK = Metrics.Chassis.CIRCUMFERENCE_INCHES | ||
public static final double METERS_PER_TICK = Metrics.Chassis.CIRCUMFERENCE_METERS | ||
/ Metrics.Chassis.TICKS_PER_REVOLUTION; | ||
} | ||
|
||
public static class Encoders { | ||
public static class TalonEncoders { | ||
public static final double TICKS_PER_REVOLUTION = 2048.0; | ||
public static final double REVOLUTIONS_PER_TICK = 1 / TICKS_PER_REVOLUTION; | ||
} | ||
|
||
public static class CANCoders { | ||
public static final double TICKS_PER_REVOLUTION = 4096.0; | ||
public static final double REVOLUTIONS_PER_TICK = 1 / TICKS_PER_REVOLUTION; | ||
} | ||
} | ||
|
||
public static class Hood { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Where are the other constants, for converting from motor spins to hood movement? |
||
public static final double LOWER_HOOD_ANGLE = 0; // TODO: Add this value | ||
public static final double RANGE_HOOD_ANGLES = 35.0; | ||
public static final double UPPER_HOOD_ANGLE = LOWER_HOOD_ANGLE + RANGE_HOOD_ANGLES; // TODO: Does having all | ||
// of these theoretical | ||
// constants negate the | ||
// zeroing we're doing? | ||
} | ||
} | ||
|
||
public static class DriveConstants { | ||
public static final boolean kGyroReversed = false; | ||
public static final double ksVolts = -1; | ||
public static final double kvVoltSecondsPerMeter = -1; | ||
public static final double kaVoltSecondsSquaredPerMeter = -1; | ||
public static final double kTrackwidthMeters = -1; | ||
public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics( | ||
kTrackwidthMeters); | ||
public static final double kPDriveVel = -1; | ||
} | ||
|
||
public static class AutoConstants { | ||
public static final double kMaxSpeedMetersPerSecond = -1; | ||
public static final double kMaxAccelerationMetersPerSecondSquared = -1; | ||
public static final double kRamseteB = -1; | ||
public static final double kRamseteZeta = -1; | ||
} | ||
|
||
public static class PID { | ||
public static class Flywheel { | ||
public static final double P = 0.0; | ||
public static final double I = 0.0; | ||
public static final double D = 0.0; | ||
public static final double F = 0.0; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. should probably copy over the values that work |
||
} | ||
|
||
public static class Hood { | ||
public static final double P = 0.0; | ||
public static final double I = 0.0; | ||
public static final double D = 0.0; | ||
public static final double F = 0.0; | ||
} | ||
|
||
public static class Drive { | ||
} | ||
|
||
|
@@ -52,9 +136,31 @@ public static class Turn { | |
} | ||
|
||
public static class Component { | ||
public static Intake intake; | ||
public static Indexer indexer; | ||
public static Flywheel flywheel; | ||
public static Shooter shooter; | ||
public static Hood hood; | ||
|
||
public static SolenoidSubsystem intakeSolenoid; | ||
public static SolenoidSubsystem flipperSolenoid; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. not using the flipper anymore |
||
public static SolenoidSubsystem shooterAimSolenoid; | ||
|
||
public static Motor intakeRollerMotor; | ||
public static Motor funnelMotor; | ||
public static Motor liftBeltMotor; | ||
public static Motor runUpBeltMotor; | ||
public static Motor flywheelMotorA; | ||
public static Motor flywheelMotorB; | ||
public static Motor hoodMotor; | ||
|
||
public static CANTalonEncoder flywheelEncoder; | ||
public static CANTalonEncoder hoodEncoder; | ||
} | ||
|
||
public static class Input { | ||
public static CustomDigitalLimitSwitch indexerLimitSwitch; | ||
public static CustomDigitalLimitSwitch hoodLimitSwitch; | ||
} | ||
|
||
public static class HumanInput { | ||
|
@@ -68,8 +174,46 @@ public static class Operator { | |
} | ||
|
||
public RobotMap() { | ||
/** Human Input */ | ||
HumanInput.Driver.xbox = new CustomXbox(Port.HumanInput.xboxController); | ||
HumanInput.Operator.joystick = new CustomJoystick(Port.HumanInput.joystick); | ||
|
||
/** Pneumatics */ | ||
Component.intakeSolenoid = new SolenoidSubsystem(Port.Pneumatics.INTAKE_SOLENOID.buildDoubleSolenoid()); | ||
Component.flipperSolenoid = new SolenoidSubsystem(Port.Pneumatics.FLIPPER_SOLENOID.buildDoubleSolenoid()); | ||
Component.shooterAimSolenoid = new SolenoidSubsystem( | ||
Port.Pneumatics.SHOOTER_AIM_SOLENOID.buildDoubleSolenoid()); | ||
|
||
/** Motors */ | ||
Component.intakeRollerMotor = new Motor("intakeRollerMotor", | ||
new CANTalonSRX(Port.CANMotor.INTAKE_ROLLER_MOTOR)); | ||
Component.funnelMotor = new Motor("funnelMotor", new CANTalonSRX(Port.CANMotor.INTAKE_FUNNEL_MOTOR)); | ||
Component.liftBeltMotor = new Motor("liftBeltMotor", new CANTalonSRX(Port.CANMotor.LIFT_BELT_MOTOR)); | ||
Component.runUpBeltMotor = new Motor("runUpBeltMotor", new CANTalonSRX(Port.CANMotor.RUN_UP_BELT_MOTOR)); | ||
CANTalonFX flywheelATalon = new CANTalonFX(Port.CANMotor.FLYWHEEL_MOTOR_A); | ||
Component.flywheelMotorA = new Motor("flywheelMotorA", flywheelATalon); | ||
Component.flywheelMotorB = new Motor("flywheelMotorB", new CANTalonFX(Port.CANMotor.FLYWHEEL_MOTOR_B)); | ||
CANTalonFX hoodTalon = new CANTalonFX(Port.CAN.HOOD_MOTOR); | ||
Component.hoodMotor = new Motor("hoodMotor", hoodTalon); | ||
|
||
/** Digital */ | ||
Input.indexerLimitSwitch = new CustomDigitalLimitSwitch(Port.Digital.INDEXER_LIMIT_SWITCH); | ||
Input.hoodLimitSwitch = new CustomDigitalLimitSwitch(Port.Digital.HOOD_LOWER_LIMIT_SWITCH); | ||
|
||
/** Encoders */ | ||
Component.flywheelEncoder = new CANTalonEncoder(flywheelATalon, | ||
Metrics.Encoders.TalonEncoders.REVOLUTIONS_PER_TICK); | ||
Component.hoodEncoder = new CANTalonEncoder(hoodTalon, Metrics.Encoders.TalonEncoders.REVOLUTIONS_PER_TICK); | ||
|
||
/** Classes */ | ||
Component.intake = new Intake(Component.intakeRollerMotor, Component.liftBeltMotor, Component.funnelMotor, | ||
Component.intakeSolenoid); | ||
Component.indexer = new Indexer(Component.flipperSolenoid, Input.indexerLimitSwitch); | ||
|
||
Component.flywheel = new Flywheel(new CustomPIDController(PID.Flywheel.P, PID.Flywheel.I, PID.Flywheel.D, | ||
PID.Flywheel.F, Component.flywheelEncoder), Component.flywheelMotorA, Component.flywheelMotorB); | ||
|
||
Component.hood = new Hood(Component.hoodMotor, Component.hoodEncoder, Input.hoodLimitSwitch); | ||
Component.shooter = new Shooter(Component.flywheel, Component.runUpBeltMotor, Component.hood); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,20 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.commands.Shoot; | ||
|
||
public class BoxShot extends Shoot { | ||
protected static final double DEFAULT_BOXSHOT_SPEED = 0.0; // TODO: Untested variables | ||
|
||
/** | ||
* Run the Shoot command for a box shot. | ||
* | ||
* | ||
* @param indexer The indexer subsystem | ||
* @param shooter The shooter subsystem | ||
* @param speed The target speed of the flywheel | ||
*/ | ||
public BoxShot() { | ||
super(DEFAULT_BOXSHOT_SPEED); | ||
setName("BoxShot"); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,15 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.RobotMap; | ||
import org.usfirst.frc4904.standard.commands.solenoid.SolenoidExtend; | ||
|
||
public class CloseIndexer extends SolenoidExtend { | ||
/** | ||
* Retract the indexer solenoid to close the indexer flippers. | ||
* | ||
* @param indexer The indexer to manipulate | ||
*/ | ||
public CloseIndexer() { | ||
super("CloseIndexer", RobotMap.Component.indexer.flippers); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,13 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.RobotMap; | ||
import org.usfirst.frc4904.standard.commands.solenoid.SolenoidExtend; | ||
|
||
public class ExtendIntake extends SolenoidExtend { | ||
/** | ||
* Extend the intake solenoid to deploy the intake rollers. | ||
*/ | ||
public ExtendIntake() { | ||
super("ExtendIntake", RobotMap.Component.intake.solenoid); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,18 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.RobotMap; | ||
import org.usfirst.frc4904.standard.commands.motor.MotorVelocitySet; | ||
|
||
public class FlywheelMaintainSpeed extends MotorVelocitySet { | ||
|
||
/** | ||
* Spin up the flywheel to a speed | ||
* | ||
* @param flywheel The flywheel to manipulate | ||
* @param speed The speed to spin the flywheel up to | ||
*/ | ||
public FlywheelMaintainSpeed(double speed) { | ||
super("FlywheelMaintainSpeed", RobotMap.Component.flywheel, speed); | ||
//addRequirements(RobotMap.Component.flywheelMotorA, RobotMap.Component.flywheelMotorB); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,32 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.subsystems.Flywheel; | ||
import edu.wpi.first.wpilibj2.command.CommandBase; | ||
|
||
public class FlywheelSpinDown extends CommandBase { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. should this also be a There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. No, because it should just set the speed of the motor 0 (we don't actually care if the motor has some excess speed, so long as it slowly approaches 0). |
||
public static final double IDLE_SPEED = 0.0; | ||
protected final Flywheel flywheel; | ||
|
||
/** | ||
* Spin down the flywheel | ||
* | ||
* @param flywheel The flywheel to manipulate | ||
*/ | ||
public FlywheelSpinDown(Flywheel flywheel) { | ||
super(); | ||
setName("FlywheelSpinDown"); | ||
addRequirements(flywheel); | ||
this.flywheel = flywheel; | ||
} | ||
|
||
@Override | ||
public void initialize() { | ||
super.initialize(); | ||
flywheel.disableMotionController(); | ||
} | ||
|
||
@Override | ||
public void execute() { | ||
NikhilSuresh24 marked this conversation as resolved.
Show resolved
Hide resolved
|
||
flywheel.set(IDLE_SPEED); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,37 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.RobotMap; | ||
import org.usfirst.frc4904.standard.commands.RunUntil; | ||
import org.usfirst.frc4904.standard.commands.motor.MotorConstant; | ||
|
||
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup; | ||
|
||
public class FlywheelSpinUp extends SequentialCommandGroup { | ||
|
||
public static final double DEFAULT_FLYWHEEL_SPEED = 0.0; // TODO: This is an untested value | ||
public static final double THRESHOLD = 0.0; | ||
|
||
/** | ||
* Spin up the flywheel to a speed | ||
* | ||
* @param flywheel The flywheel to manipulate | ||
* @param speed The speed to spin the flywheel up to | ||
*/ | ||
public FlywheelSpinUp(double speed) { | ||
// smartdashboard.getNumber(“setpoint”, 0) | ||
super(new RunUntil("FlywheelSpinUp", new MotorConstant(RobotMap.Component.flywheel, speed), () -> { | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. it should be speed times feedfoward, not just raw speed |
||
return Math.abs(RobotMap.Component.shooter.flywheel.getTargetSpeed() - speed) < THRESHOLD | ||
|| RobotMap.Component.shooter.flywheel.getTargetSpeed() > speed; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. there should also be a |
||
}), new FlywheelMaintainSpeed(speed)); | ||
addRequirements(RobotMap.Component.flywheelMotorA, RobotMap.Component.flywheelMotorB); | ||
} | ||
|
||
/** | ||
* Spin up the flywheel to the default speed | ||
* | ||
* @param flywheel The flywheel to manipulate | ||
*/ | ||
public FlywheelSpinUp() { | ||
this(DEFAULT_FLYWHEEL_SPEED); | ||
} | ||
} |
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,24 @@ | ||
package org.usfirst.frc4904.robot.commands; | ||
|
||
import org.usfirst.frc4904.robot.RobotMap; | ||
import org.usfirst.frc4904.standard.commands.motor.MotorConstant; | ||
|
||
/** | ||
* Goes to the lower limit and zeroes | ||
*/ | ||
public class HoodZeroConstant extends MotorConstant { | ||
public final static double DEFAULT_SPEED = 0; | ||
|
||
public HoodZeroConstant() { | ||
super("HoodZeroConstant", RobotMap.Component.hood.getServo(), DEFAULT_SPEED); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. the servo no longer exists |
||
} | ||
|
||
@Override | ||
public void end(boolean interrupted) { | ||
super.end(interrupted); | ||
if (!interrupted) { | ||
RobotMap.Component.hood.setLimit(); | ||
} | ||
} | ||
|
||
} |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
No hood encoder—we'll use the encoder that's built into the falcon that's driving the hood.