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

Shooter #14

Open
wants to merge 15 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 8 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
1 change: 1 addition & 0 deletions .classpath
Original file line number Diff line number Diff line change
Expand Up @@ -6,5 +6,6 @@
<classpathentry kind="var" path="opencv" sourcepath="opencv.sources"/>
<classpathentry kind="var" path="cscore" sourcepath="cscore.sources"/>
<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER"/>
<classpathentry kind="var" path="USERLIBS_DIR/CTRLib.jar"/>
<classpathentry kind="output" path="bin"/>
</classpath>
1 change: 1 addition & 0 deletions src/com/nutrons/nu17/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@ public OI() {
this.RAISE_PLACER.whenPressed(new RaiseGearPlacerCmd());
this.LOWER_PLACER.whenPressed(new LowerGearPlacerCmd());
this.SHOOT.whenPressed(new ShootShooterCmd());
this.SHOOT.whenReleased(new StopShooterCmd());
this.INTAKE.whenPressed(new GroundIntakeCmd());
this.INTAKE_SPIT.whenPressed(new GroundIntakeSpitCmd());
}
Expand Down
26 changes: 21 additions & 5 deletions src/com/nutrons/nu17/Robot.java
Original file line number Diff line number Diff line change
@@ -1,26 +1,34 @@
package com.nutrons.nu17;

import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

import com.nutrons.nu17.OI;
import com.nutrons.nu17.subsystems.*;

public class Robot extends IterativeRobot {

public final static TwinShooter TWIN_SHOOTER = new TwinShooter();
public final static Shooter SHOOTER = new Shooter();
public static Shooter SHOOTER = new Shooter();
public final static GroundIntake GROUND_INTAKE = new GroundIntake();
public final static DrivetrainGyro DT = new DrivetrainGyro();
public final static GearPlacer GP = new GearPlacer();
public final static Drivetrain DRIVE_TRAIN = new Drivetrain();
public final static Climber CLIMBER = new Climber();

public final static OI OI = new OI();
Preferences prefs;

Command autonomousCommand;
SendableChooser <Command> chooser = new SendableChooser<>();

@Override
public void robotInit() {
//empty
SmartDashboard.putData("Auto mode", chooser);
}

@Override
Expand All @@ -35,7 +43,10 @@ public void disabledPeriodic() {

@Override
public void autonomousInit() {
//empty
autonomousCommand = chooser.getSelected();

if (autonomousCommand !=null)
autonomousCommand.start();
}

@Override
Expand All @@ -45,16 +56,21 @@ public void autonomousPeriodic() {

@Override
public void teleopInit() {
//empty
prefs = Preferences.getInstance();
Shooter.SHOOTER_SPEED = prefs.getDouble("shooter_speed", 1.0);
}

@Override
public void teleopPeriodic() {
Scheduler.getInstance().run();


SmartDashboard.putNumber("current_shooter_power", Robot.SHOOTER.getRPM());
}

@Override
public void testPeriodic() {
LiveWindow.run();
}

}
23 changes: 12 additions & 11 deletions src/com/nutrons/nu17/commands/ShootShooterCmd.java
Original file line number Diff line number Diff line change
@@ -1,11 +1,13 @@
package com.nutrons.nu17.commands;

import com.ctre.CANTalon.TalonControlMode;
import com.nutrons.nu17.Robot;
import com.nutrons.nu17.subsystems.Shooter;

import edu.wpi.first.wpilibj.command.Command;

public class ShootShooterCmd extends Command {

public ShootShooterCmd() {
requires(Robot.SHOOTER);
}
Expand All @@ -14,26 +16,25 @@ public ShootShooterCmd() {
* Resets encoder and starts running motor at a consistent speed.
*/
protected void initialize() {
Robot.SHOOTER.resetEncoder();
Robot.SHOOTER.runShooter(1.0);
Robot.SHOOTER.SHOOTER.changeControlMode(TalonControlMode.Speed);
Robot.SHOOTER.SHOOTER.setSetpoint(Shooter.SHOOTER_SPEED);
Robot.SHOOTER.SHOOTER.enable();
}

/**
* Keeps running motor to a consistent speed.
*/
protected void execute() {
Robot.SHOOTER.runShooter(Robot.SHOOTER.SPEED_PID.get());

}

// Don't want the shooter to stop
protected boolean isFinished() {
return false;
return true;
}

protected void end() {
Robot.SHOOTER.stopShooter();

}

protected void interrupted() {
end();

}
}
34 changes: 34 additions & 0 deletions src/com/nutrons/nu17/commands/StopShooterCmd.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
package com.nutrons.nu17.commands;

import com.nutrons.nu17.Robot;

import edu.wpi.first.wpilibj.command.Command;


public class StopShooterCmd extends Command {

public StopShooterCmd() {
requires(Robot.SHOOTER);
}

protected void initialize() {
Robot.SHOOTER.SHOOTER.disable();
}


protected void execute() {
}


protected boolean isFinished() {
return true;
}


protected void end() {
}


protected void interrupted() {
}
}
79 changes: 47 additions & 32 deletions src/com/nutrons/nu17/subsystems/Shooter.java
Original file line number Diff line number Diff line change
@@ -1,69 +1,84 @@
package com.nutrons.nu17.subsystems;

import com.ctre.CANTalon;
import com.ctre.CANTalon.FeedbackDevice;
import com.ctre.CANTalon.TalonControlMode;
import com.nutrons.nu17.Robot;
import com.nutrons.nu17.RobotMap;
import com.nutrons.nu17.commands.ShootShooterCmd;

import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PIDController;
import edu.wpi.first.wpilibj.PIDSourceType;
import edu.wpi.first.wpilibj.Talon;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import lib.EncoderWrapper;
import lib.HoldPID;

public class Shooter extends Subsystem {

private final Talon SHOOTER = new Talon(RobotMap.SHOOTER);
private final Encoder SHOOTER_ENCODER = new Encoder(
RobotMap.SHOOT_ENCODER_1,
RobotMap.SHOOT_ENCODER_2);
private EncoderWrapper encWrap = new EncoderWrapper(
PIDSourceType.kDisplacement,
SHOOTER_ENCODER,
RobotMap.SHOOT_ENCODER_1,
RobotMap.SHOOT_ENCODER_2);

private HoldPID shootHold = new HoldPID();
public static double SHOOTER_SPEED = 10.0;

public Shooter() {
//empty
}
public CANTalon SHOOTER = new CANTalon(RobotMap.SHOOTER);

// TODO: tune these constants
private static final double P_SHOOT = 0.025;
private static final double I_SHOOT = 0.0;
private static final double D_SHOOT = 0.01;
public static double P_SHOOT = 0.025;
public static double I_SHOOT = 0.0;
public static double D_SHOOT = 0.01;
public static double F_SHOOT = 0.025;

public final PIDController SPEED_PID = new PIDController(
P_SHOOT,
I_SHOOT,
D_SHOOT,
encWrap,
shootHold);
public Shooter() {
this.SHOOTER.configNominalOutputVoltage(+0.0f, -0.0f);
this.SHOOTER.configPeakOutputVoltage(+12.0f, 0.0f);
this.SHOOTER.configEncoderCodesPerRev((int)(256 / 0.14));
this.SHOOTER.configEncoderCodesPerRev((int)(256 / 0.14));
this.SHOOTER.setFeedbackDevice(FeedbackDevice.QuadEncoder);
this.SHOOTER.setP(P_SHOOT);
this.SHOOTER.setI(I_SHOOT);
this.SHOOTER.setD(D_SHOOT);
this.SHOOTER.setF(F_SHOOT);

}

public void initDefaultCommand() {
setDefaultCommand(new ShootShooterCmd());

}

/**
* Runs shooter at given param power.
*
* @param power Speed to run the shooting motor.
* Changes to manual and sets the speed
* @param speed Speed of shooter
*/
public void runShooter(double power) {
this.SHOOTER.set(power);
public void setOpenLoop(double speed){
this.SHOOTER.changeControlMode(TalonControlMode.PercentVbus);
this.SHOOTER.set(speed);
}
/**
* Changes to closed loop.
* Sets the RPM from the shooter
*/
public void setRPM(double rpm){
this.SHOOTER.changeControlMode(TalonControlMode.Speed);
this.SHOOTER.set(rpm);
}

/**
* Cuts the power to the shooter, setting it to 0.0.
*/
public void stopShooter() {
runShooter(0.0);
setOpenLoop(0.0);
}
/**
*
* Gets RPM from shooter
*/
public double getRPM(){
return this.SHOOTER.getSpeed();
}

/**
* Resets Encoder.
*/
public void resetEncoder() {
SHOOTER_ENCODER.reset();
this.SHOOTER.setEncPosition(0);
}
}
8 changes: 4 additions & 4 deletions src/com/nutrons/nu17/subsystems/TwinShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ public void initDefaultCommand() {
* @param power Speed to run the first shooting motor at.
*/
public void runTwinA(double power) {
TWIN_A.runShooter(power);
TWIN_A.setRPM(power);
}

/**
Expand All @@ -81,7 +81,7 @@ public void runTwinA(double power) {
* @param power Speed to run the second shooting motor at.
*/
public void runTwinB(double power) {
TWIN_B.runShooter(power);
TWIN_B.setRPM(power);
}

/**
Expand All @@ -98,14 +98,14 @@ public void twinRun(double power) {
* Stops the first shooting motor.
*/
public void stopTwinA() {
TWIN_A.runShooter(0.0);
TWIN_A.setRPM(0.0);
}

/**
* Stops the second shooting motor.
*/
public void stopTwinB() {
TWIN_B.runShooter(0.0);
TWIN_B.setRPM(0.0);
}

/**
Expand Down