Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
ashton-mitchell committed Feb 19, 2020
2 parents 7e1c38b + 9047721 commit 41bc6a5
Show file tree
Hide file tree
Showing 13 changed files with 209 additions and 124 deletions.
Binary file modified FRC2020/.gradle/6.0.1/executionHistory/executionHistory.bin
Binary file not shown.
Binary file modified FRC2020/.gradle/6.0.1/executionHistory/executionHistory.lock
Binary file not shown.
Binary file modified FRC2020/.gradle/6.0.1/fileHashes/fileHashes.bin
Binary file not shown.
Binary file modified FRC2020/.gradle/6.0.1/fileHashes/fileHashes.lock
Binary file not shown.
Binary file modified FRC2020/.gradle/6.0.1/javaCompile/classAnalysis.bin
Binary file not shown.
Binary file modified FRC2020/.gradle/6.0.1/javaCompile/javaCompile.lock
Binary file not shown.
Binary file modified FRC2020/.gradle/buildOutputCleanup/buildOutputCleanup.lock
Binary file not shown.
38 changes: 22 additions & 16 deletions FRC2020/src/main/java/frc/robot/Cartridge/pistonlift.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,22 +3,28 @@
import frc.robot.Map;

public class pistonlift {
public static void pistons() {
if (Map.Controllers.driverLeft.getRawButton(1) || Map.Controllers.driverRight.getRawButton(1)) {
Map.Cartridge.RightPiston.set(true);
Map.Cartridge.LeftPiston.set(true);

} else {
Map.Cartridge.RightPiston.set(false);
Map.Cartridge.LeftPiston.set(false);
}

}
public static void PistonRoller() {
if (Map.Controllers.driverLeft.getRawButton(1) || Map.Controllers.driverRight.getRawButton(1) ) {
private static boolean pistonactive = false;
public static void run() {
if (Map.Controllers.driverLeft.getRawButtonPressed(1)) {
if(!pistonactive){
Map.Cartridge.RightPiston.set(true);
pistonactive = true;
}else{
Map.Cartridge.RightPiston.set(false);
Map.Cartridge.ArmRoller.set(ControlMode.PercentOutput, 0);
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, 0);
pistonactive = false;
}
}
if(Map.Controllers.driverRight.getRawButton(1)){
Map.Cartridge.ArmRoller.set(ControlMode.PercentOutput, 1);
}else{
Map.Cartridge.ArmRoller.set(ControlMode.PercentOutput, 0);
}
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, -0.25);
}else if(Map.Controllers.driverRight.getRawButton(5)){
Map.Cartridge.ArmRoller.set(ControlMode.PercentOutput, -1);
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, 1);
}else{
Map.Cartridge.ArmRoller.set(ControlMode.PercentOutput, 0);
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, 0);
}
}
}
33 changes: 19 additions & 14 deletions FRC2020/src/main/java/frc/robot/Map.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel.MotorType;
import com.revrobotics.ColorSensorV3;
import com.revrobotics.ColorSensorV3.RawColor;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.I2C;
import edu.wpi.first.wpilibj.Joystick;
Expand All @@ -20,10 +19,10 @@ public class Map {
// Where all controllers and gamepads are stored
public static class driveTrain{
// Drive Train Motors
public static CANSparkMax lf = new CANSparkMax(0, MotorType.kBrushless);
public static CANSparkMax lr = new CANSparkMax(1, MotorType.kBrushless);
public static CANSparkMax rf = new CANSparkMax(2, MotorType.kBrushless);
public static CANSparkMax rr = new CANSparkMax(3, MotorType.kBrushless);
public static CANSparkMax lf = new CANSparkMax(1, MotorType.kBrushless);
public static CANSparkMax lr = new CANSparkMax(2, MotorType.kBrushless);
public static CANSparkMax rf = new CANSparkMax(3, MotorType.kBrushless);
public static CANSparkMax rr = new CANSparkMax(4, MotorType.kBrushless);

//Drive Train Encoders
public static CANEncoder lfEncoder = lf.getEncoder();
Expand All @@ -42,24 +41,30 @@ public static class Turret{
// Turret Motors
public static class motors{
// Rotation motors
public static TalonSRX rotation = new TalonSRX(4);
public static TalonSRX rotation = new TalonSRX(5);
// Launching Motors
public static TalonSRX launcher = new TalonSRX(5);
public static TalonSRX follower = new TalonSRX(6);
public static TalonSRX launcher = new TalonSRX(9);
public static TalonSRX follower = new TalonSRX(7);
}
public static class controllers{
public static int initiation = 5; // Raw button number for launching initiation
public static int launch = 6; // Raw button number for launching ball
public static int manuelRotateLarge = 0;
public static int manuelRotateSmall = 2;
public static int manuelLauncherAddPower = 4;
public static int manuelLauncherSubtractPower = 2;
public static int manuelMode = 10; // button that changes remote into manuel
}
}
public static class Cartridge{
// Cartridge / Loading-Arm motors (and pneumatics)
public static Solenoid RightPiston = new Solenoid (1,1);
public static Solenoid LeftPiston = new Solenoid (2,2);
public static TalonSRX ArmRoller = new TalonSRX(7);
public static TalonSRX Conveyor1 = new TalonSRX(8);
public static TalonSRX Conveyor2 = new TalonSRX(9);
public static TalonSRX Conveyor3 = new TalonSRX(10);
public static Solenoid RightPiston = new Solenoid(1, 4);
//private static Solenoid test = new Solenoid(4);
//public static Solenoid LeftPiston = new Solenoid (2,2);
public static TalonSRX ArmRoller = new TalonSRX(2);
public static TalonSRX Conveyor1 = new TalonSRX(4);
public static TalonSRX Conveyor2 = new TalonSRX(3);
public static TalonSRX Conveyor3 = new TalonSRX(8);
public static class Sensors{
public static DigitalInput fullSensor = new DigitalInput(0);

Expand Down
26 changes: 19 additions & 7 deletions FRC2020/src/main/java/frc/robot/TeleOp/DriveTrain.Java
Original file line number Diff line number Diff line change
@@ -1,13 +1,17 @@
package frc.robot.TeleOp;

import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.SparkMax;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.robot.Map;

/**
* DriveTrain
*/
public class DriveTrain {

private static double deadBand = 0.05;
public static double ticksToFeet = 6 * Math.PI / 84;

public static void drive(){
Expand All @@ -27,11 +31,19 @@ public class DriveTrain {
final double lr = leftY + leftX;
final double rr = rightY - rightX;
// returns the final movement variables

Map.driveTrain.lf.set(lf);
Map.driveTrain.lr.set(lr);
Map.driveTrain.rf.set(rf);
Map.driveTrain.rr.set(rr);

powerManagement(Map.driveTrain.lf, lf);
powerManagement(Map.driveTrain.lr, lr);
powerManagement(Map.driveTrain.rf, rf);
powerManagement(Map.driveTrain.rr, rr);
SmartDashboard.putNumber("Driver Left", Map.Controllers.driverLeft.getY());
SmartDashboard.putNumber("Driver Right", Map.Controllers.driverRight.getY());
}
private static void powerManagement(CANSparkMax motor, double pwr){
double abspwr = Math.abs(pwr);
if(abspwr>deadBand){
motor.set(pwr);
}else{
motor.set(0);
}
}
}
127 changes: 73 additions & 54 deletions FRC2020/src/main/java/frc/robot/Turret/Targeting.java
Original file line number Diff line number Diff line change
@@ -1,128 +1,147 @@
package frc.robot.Turret;

import com.ctre.phoenix.motorcontrol.ControlMode;

import frc.robot.Map;
import frc.robot.Cartridge.Conveyor;
import frc.robot.Vision.LimeLight;

/**
* Targeting
*/
public class Targeting {
// Customizable Settings
// Turret Rotation Settings
private static double slopePoint = 1/27; // Point at which turret uses slope formula to turn
private static double trackingerror = 1/27; // X axis distange from 0 error range
// Launching Settings
public static double launchingSpeedAddition = 50; // additional power added to launching function
private static double maxLaunchingSpeedError = 20; // maximum velocity error for launcher
private static double baseLaunchSpeed = 200; // init speed (so that its close to target launch speed)
// Turret Rotation Settings
private static double slopePoint = 1; // Point at which turret uses slope formula to turn
private static double trackingerror = 0.05; // X axis distange from 0 error range
// Launching Settings
public static double launchingSpeedAddition = 50; // additional power added to launching function
private static double maxLaunchingSpeedError = 20; // maximum velocity error for launcher
private static double baseLaunchSpeed = 200; // init speed (so that its close to target launch speed)

// Method Settings
private static boolean track = false; // tracks target as long as true
private static boolean targetZeroedIn = false; // true if target is within trackingerror
private static boolean maintainLaunchingSpeed = false; // keeps launcher loop up to speed as long as true
private static boolean launcherUpToSpeed = false; // nofifies if launcher is at wanted velocity
private static boolean maintainBaseLaunchSpeed = false; // maintains a basic launching velocity while true
/*
Example data:
180 Degrees of rotation
y and x (on LimeLight) range from -1 to 1
*/
public static void initilize(){
private static boolean track = false; // tracks target as long as true
private static boolean targetZeroedIn = false; // true if target is within trackingerror
private static boolean maintainLaunchingSpeed = false; // keeps launcher loop up to speed as long as true
private static boolean launcherUpToSpeed = false; // nofifies if launcher is at wanted velocity
private static boolean maintainBaseLaunchSpeed = false; // maintains a basic launching velocity while true
/*
* Example data: 180 Degrees of rotation y and x (on LimeLight) range from -1 to
* 1
*/

public static void initilize() {
// Starts tracking process
LimeLight.LED.on();
// Sets launching motors at base speed
Thread setBaseLaunchingSpeed = new Thread(){
public void run(){
Thread setBaseLaunchingSpeed = new Thread() {
public void run() {
setBaseLaunchingSpeed();
}
};
// Gets turret into position to launch
Thread followingThread = new Thread(){
Thread followingThread = new Thread() {
public void run() {
trackTarget();
}
};
// Gets turret up to speed and ready to launch
Thread firingThread = new Thread(){
public void run(){
Thread firingThread = new Thread() {
public void run() {
initLauncher();
}
};
setBaseLaunchingSpeed.start();
followingThread.start();
firingThread.start();
}
public static boolean readyToFire(){
if(launcherUpToSpeed&&targetZeroedIn){

public static boolean readyToFire() {
if (launcherUpToSpeed && targetZeroedIn) {
return true;
}else{
} else {
return false;
}
}
public static void stop(){
//stops targeting

public static void stop() {
// stops targeting
track = false;
targetZeroedIn = false;
maintainLaunchingSpeed = false;
launcherUpToSpeed = false;
maintainBaseLaunchSpeed = false;
LimeLight.LED.off();
}
private static void setBaseLaunchingSpeed(){
while(maintainBaseLaunchSpeed){

private static void setBaseLaunchingSpeed() {
while (maintainBaseLaunchSpeed) {
TurretMotion.Launcher.setVelocity(baseLaunchSpeed);
}
}

private static void findTarget() {
// Finds target
if(!LimeLight.isTarget()){
while(!LimeLight.isTarget()){
if(TurretMotion.Rotation.getDegrees()>=90){
while(TurretMotion.Rotation.getDegrees()<180||(!LimeLight.isTarget())){
if (!LimeLight.isTarget()) {
while (!LimeLight.isTarget()) {
if (TurretMotion.Rotation.getDegrees() >= 90) {
while (TurretMotion.Rotation.getDegrees() < 180 || (!LimeLight.isTarget())) {
TurretMotion.Rotation.turn(1);
}
}else{
while(TurretMotion.Rotation.getDegrees()>0||(!LimeLight.isTarget())){
} else {
while (TurretMotion.Rotation.getDegrees() > 0 || (!LimeLight.isTarget())) {
TurretMotion.Rotation.turn(-1);
}
}
}
}
}
public static void launch(){
if(launcherUpToSpeed&&targetZeroedIn){
// load ball into chamber (Owens code)
}

public static void launch() {
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, 0.5);
Map.Cartridge.Conveyor2.set(ControlMode.PercentOutput, -0.5);
Map.Cartridge.Conveyor3.set(ControlMode.PercentOutput, 0.5);
// load ball into chamber (Owens code)
}
private static void initLauncher(){
//maintains a launch speed (will need to be in a thread)
maintainBaseLaunchSpeed = false; //overrides base launch code
public static void stopLaunch(){
Map.Cartridge.Conveyor1.set(ControlMode.PercentOutput, 0);
Map.Cartridge.Conveyor2.set(ControlMode.PercentOutput, 0);
Map.Cartridge.Conveyor3.set(ControlMode.PercentOutput, 0);
}

private static void initLauncher() {
// maintains a launch speed (will need to be in a thread)
maintainBaseLaunchSpeed = false; // overrides base launch code
double motorSpeed = TurretMotion.Launcher.getVelocity();
double targetSpeed = calculateLaunchSpeed();
double abserror = Math.abs(targetSpeed-motorSpeed);
double error = targetSpeed-motorSpeed;
while(maintainLaunchingSpeed){
double abserror = Math.abs(targetSpeed - motorSpeed);
double error = targetSpeed - motorSpeed;
while (maintainLaunchingSpeed) {
motorSpeed = TurretMotion.Launcher.getVelocity();
targetSpeed = calculateLaunchSpeed();
abserror = Math.abs(targetSpeed-motorSpeed);
if(abserror>maxLaunchingSpeedError){
abserror = Math.abs(targetSpeed - motorSpeed);
if (abserror > maxLaunchingSpeedError) {
launcherUpToSpeed = false;
TurretMotion.Launcher.setVelocity(targetSpeed-error);// might be minus error (too tired to think rn)
}else{
TurretMotion.Launcher.setVelocity(targetSpeed - error);// might be minus error (too tired to think rn)
} else {
launcherUpToSpeed = true;
}
}
}
private static double calculateLaunchSpeed(){

private static double calculateLaunchSpeed() {
// Finds the speed of the flywheen needed to hit the target
double y = LimeLight.getY();
double output = (y)+launchingSpeedAddition; // replace 'y' with custom function
double output = (y) + launchingSpeedAddition; // replace 'y' with custom function
return output;
}
private static void trackTarget(){

private static void trackTarget() {
// Lines turret to center of target
double position = LimeLight.getX();
double error = Math.abs(position);
track = true;
LimeLight.LED.on();
while(track){
if(LimeLight.isTarget()&&track){
position = LimeLight.getX();
Expand All @@ -144,7 +163,7 @@ private static void trackTarget(){
targetZeroedIn = true;
TurretMotion.Rotation.turn(0);
}else{
findTarget();
//findTarget();
}
}
}
Expand Down
Loading

0 comments on commit 41bc6a5

Please sign in to comment.