diff --git a/Pathgen/lib/Pathfinder-Java.jar b/Pathgen/lib/Pathfinder-Java.jar index 5186498b..d3730e95 100644 Binary files a/Pathgen/lib/Pathfinder-Java.jar and b/Pathgen/lib/Pathfinder-Java.jar differ diff --git a/Pathgen/src/main/java/org/usfirst/frc/team449/pathgen/Pathgen.java b/Pathgen/src/main/java/org/usfirst/frc/team449/pathgen/Pathgen.java index ee086c36..7ea3567e 100644 --- a/Pathgen/src/main/java/org/usfirst/frc/team449/pathgen/Pathgen.java +++ b/Pathgen/src/main/java/org/usfirst/frc/team449/pathgen/Pathgen.java @@ -14,25 +14,27 @@ * Generates a motion profile that hits any number of waypoints. */ public class Pathgen { + public static void main(String[] args) throws IOException { - final double CENTER_TO_FRONT = 27./2.; - final double CENTER_TO_BACK = 27./2. + 3.25; - final double CENTER_TO_SIDE = 29./2. + 3.25; + final double CENTER_TO_FRONT = 27. / 2.; + final double CENTER_TO_BACK = 27. / 2. + 3.25; + final double CENTER_TO_SIDE = 29. / 2. + 3.25; final double BACK_FROM_PEG = -5; //DO NOT TOUCH THE ONES BELOW final double CARRIAGE_LEN = 3.63; - final double BLUE_WALL_TO_CENTER_PEG = 113.75; - final double BLUE_WALL_TO_SIDE_PEG = 130.75; - final double BLUE_BACK_CORNER_TO_SIDE_PEG = 91.; - final double BLUE_HALF_KEY_LENGTH = 150.5/2.; - final double BLUE_KEY_CORNER_TO_SIDE_PEG = 15.; - final double RED_WALL_TO_CENTER_PEG = 114.; - final double RED_WALL_TO_SIDE_PEG = 130.; - final double RED_BACK_CORNER_TO_SIDE_PEG = 93.5; - final double RED_HALF_KEY_LENGTH = 152.5/2.; - final double RED_KEY_CORNER_TO_SIDE_PEG = 18.75; - final double AIRSHIP_PARALLEL_OFFSET = 6.; + final double BLUE_WALL_TO_CENTER_PEG = 114.; + final double BLUE_WALL_TO_SIDE_PEG = 130.5; + final double BLUE_BACK_CORNER_TO_SIDE_PEG = 89.; + final double BLUE_HALF_KEY_LENGTH = 152. / 2.; + final double BLUE_KEY_CORNER_TO_SIDE_PEG = 16.; + final double RED_WALL_TO_CENTER_PEG = 113.5; + final double RED_WALL_TO_SIDE_PEG = 131.; + final double RED_BACK_CORNER_TO_SIDE_PEG = 97.; + final double RED_HALF_KEY_LENGTH = 152. / 2.; + final double RED_KEY_CORNER_TO_SIDE_PEG = 21.; + final double AIRSHIP_PARALLEL_OFFSET_BLUE = 1.; + final double AIRSHIP_PARALLEL_OFFSET_RED = 2.; final double PEG_BASE_TO_CENTER = CENTER_TO_FRONT + CARRIAGE_LEN + BACK_FROM_PEG; @@ -43,86 +45,86 @@ public static void main(String[] args) throws IOException { Waypoint[] blueLeft = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((BLUE_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.cos(5.*Math.PI/6.))/12. - ,-(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.sin(5.*Math.PI/6.))/12.,-Math.PI/3.) + new Waypoint((BLUE_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.cos(5. * Math.PI / 6.)) / 12. + , -(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.sin(5. * Math.PI / 6.)) / 12., -Math.PI / 3.) }; Waypoint[] blueRight = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((BLUE_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.cos(5.*Math.PI/6.))/12. - ,(BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.sin(5.*Math.PI/6.))/12.,Math.PI/3.) + new Waypoint((BLUE_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.cos(5. * Math.PI / 6.)) / 12. + , (BLUE_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_BLUE * Math.sin(5. * Math.PI / 6.)) / 12., Math.PI / 3.) }; Waypoint[] blueCenter = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((BLUE_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER)/12., 0, 0) + new Waypoint((BLUE_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER) / 12., 0, 0) }; Waypoint[] redLeft = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((RED_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.cos(5.*Math.PI/6.))/12. - ,-(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.sin(5.*Math.PI/6.))/12.,-Math.PI/3.) + new Waypoint((RED_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.cos(5. * Math.PI / 6.)) / 12. + , -(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.sin(5. * Math.PI / 6.)) / 12., -Math.PI / 3.) }; Waypoint[] redRight = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((RED_WALL_TO_SIDE_PEG-CENTER_TO_BACK - 0.5*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.cos(5.*Math.PI/6.))/12. - ,(RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.)/2.)*PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET*Math.sin(5.*Math.PI/6.))/12.,Math.PI/3.) + new Waypoint((RED_WALL_TO_SIDE_PEG - CENTER_TO_BACK - 0.5 * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.cos(5. * Math.PI / 6.)) / 12. + , (RED_BACK_CORNER_TO_SIDE_PEG - CENTER_TO_SIDE - (Math.sqrt(3.) / 2.) * PEG_BASE_TO_CENTER + AIRSHIP_PARALLEL_OFFSET_RED * Math.sin(5. * Math.PI / 6.)) / 12., Math.PI / 3.) }; Waypoint[] redCenter = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((RED_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER)/12., 0, 0) + new Waypoint((RED_WALL_TO_CENTER_PEG - CENTER_TO_BACK - PEG_BASE_TO_CENTER) / 12., 0, 0) }; Waypoint[] redPegToKey = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((PEG_BASE_TO_CENTER*Math.cos(Math.toRadians(180)) + RED_WALL_TO_SIDE_PEG*Math.cos(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG*Math.cos(Math.toRadians(30)) - + RED_HALF_KEY_LENGTH*Math.cos(Math.toRadians(75)) + CENTER_TO_BACK*Math.cos(Math.toRadians(165)))/12., - (RED_WALL_TO_SIDE_PEG*Math.sin(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG*Math.sin(Math.toRadians(30)) - + RED_HALF_KEY_LENGTH*Math.sin(Math.toRadians(75)) + CENTER_TO_BACK*Math.sin(Math.toRadians(165)))/12., + new Waypoint((PEG_BASE_TO_CENTER * Math.cos(Math.toRadians(180)) + RED_WALL_TO_SIDE_PEG * Math.cos(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG * Math.cos(Math.toRadians(30)) + + RED_HALF_KEY_LENGTH * Math.cos(Math.toRadians(75)) + CENTER_TO_BACK * Math.cos(Math.toRadians(165))) / 12., + (RED_WALL_TO_SIDE_PEG * Math.sin(Math.toRadians(-60)) + RED_KEY_CORNER_TO_SIDE_PEG * Math.sin(Math.toRadians(30)) + + RED_HALF_KEY_LENGTH * Math.sin(Math.toRadians(75)) + CENTER_TO_BACK * Math.sin(Math.toRadians(165))) / 12., -Math.toRadians(16)) }; Waypoint[] bluePegToKey = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint((PEG_BASE_TO_CENTER*Math.cos(Math.toRadians(180)) + BLUE_WALL_TO_SIDE_PEG*Math.cos(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG*Math.cos(Math.toRadians(-30)) - + BLUE_HALF_KEY_LENGTH*Math.cos(Math.toRadians(-75)) + CENTER_TO_BACK*Math.cos(Math.toRadians(-165)))/12., - (BLUE_WALL_TO_SIDE_PEG*Math.sin(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG*Math.sin(Math.toRadians(-30)) - + BLUE_HALF_KEY_LENGTH*Math.sin(Math.toRadians(-75)) + CENTER_TO_BACK*Math.sin(Math.toRadians(-165)))/12., + new Waypoint((PEG_BASE_TO_CENTER * Math.cos(Math.toRadians(180)) + BLUE_WALL_TO_SIDE_PEG * Math.cos(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG * Math.cos(Math.toRadians(-30)) + + BLUE_HALF_KEY_LENGTH * Math.cos(Math.toRadians(-75)) + CENTER_TO_BACK * Math.cos(Math.toRadians(-165))) / 12., + (BLUE_WALL_TO_SIDE_PEG * Math.sin(Math.toRadians(60)) + BLUE_KEY_CORNER_TO_SIDE_PEG * Math.sin(Math.toRadians(-30)) + + BLUE_HALF_KEY_LENGTH * Math.sin(Math.toRadians(-75)) + CENTER_TO_BACK * Math.sin(Math.toRadians(-165))) / 12., Math.toRadians(16)) }; Waypoint[] backupRed = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint(3, 1, Math.PI/3) + new Waypoint(3, 1, Math.PI / 3) }; Waypoint[] backupBlue = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint(3, -1, -Math.PI/3) + new Waypoint(3, -1, -Math.PI / 3) }; Waypoint[] blueLoadingToLoading = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint(27, -5, 0) + new Waypoint(22, -5, 0) }; Waypoint[] blueBoilerToLoading = new Waypoint[]{ new Waypoint(0, 0, 0), new Waypoint(5, 0, 0), - new Waypoint(27, -15, 0) + new Waypoint(22, -15, 0) }; Waypoint[] redLoadingToLoading = new Waypoint[]{ new Waypoint(0, 0, 0), - new Waypoint(27, 5, 0) + new Waypoint(22, 5, 0) }; Waypoint[] redBoilerToLoading = new Waypoint[]{ new Waypoint(0, 0, 0), new Waypoint(5, 0, 0), - new Waypoint(27, 15, 0) + new Waypoint(22, 15, 0) }; Map profiles = new HashMap<>(); @@ -136,25 +138,28 @@ public static void main(String[] args) throws IOException { profiles.put("BlueShoot", bluePegToKey); profiles.put("RedBackup", backupRed); profiles.put("BlueBackup", backupBlue); + profiles.put("forward100In", points); + profiles.put("BlueBackup", backupBlue); profiles.put("BlueLoadingToLoading", blueLoadingToLoading); profiles.put("BlueBoilerToLoading", blueBoilerToLoading); profiles.put("RedLoadingToLoading", redLoadingToLoading); profiles.put("RedBoilerToLoading", redBoilerToLoading); +// profiles.put("forward100In", points); final String ROBOT_NAME = "calcifer"; //Calculated by driving each wheel n inches in opposite directions, then taking the angle moved, θ, and finding // the circumference of a circle moved by the robot via C = 360 * n / θ //You then find the diameter via C / π. - double balbasaurWheelbase = 33.3 / 12.; + double balbasaurWheelbase = 30. / 12.; //200 in: 29.96 //50 in: 34.2 //433.415 - double calciferWheelbase = 26./12.; + double calciferWheelbase = 26. / 12.; Trajectory.Config config = new Trajectory.Config(Trajectory.FitMethod.HERMITE_CUBIC, Trajectory.Config.SAMPLES_HIGH, - 0.05, 5., 3, 6); //Units are seconds, feet/second, feet/(second^2), and feet/(second^3) + 0.05, 5., 4.5, 9.); //Units are seconds, feet/second, feet/(second^2), and feet/(second^3) for (String profile : profiles.keySet()) { Trajectory trajectory = Pathfinder.generate(profiles.get(profile), config); @@ -168,14 +173,14 @@ public static void main(String[] args) throws IOException { lfw.write(tm.getLeftTrajectory().length() + "\n"); for (int i = 0; i < tm.getLeftTrajectory().length(); i++) { lfw.write(tm.getLeftTrajectory().get(i).position + ",\t" + tm.getLeftTrajectory().get(i).velocity + ",\t" - + tm.getLeftTrajectory().get(i).dt + ","); + + tm.getLeftTrajectory().get(i).acceleration + ",\t" + tm.getLeftTrajectory().get(i).dt); lfw.write("\n"); } rfw.write(tm.getRightTrajectory().length() + "\n"); for (int i = 0; i < tm.getRightTrajectory().length(); i++) { - rfw.write(tm.getRightTrajectory().get(i).position + ",\t" + tm.getRightTrajectory().get(i).velocity + "," + - "\t" + tm.getRightTrajectory().get(i).dt + ","); + rfw.write(tm.getRightTrajectory().get(i).position + ",\t" + tm.getRightTrajectory().get(i).velocity + + ",\t" + tm.getLeftTrajectory().get(i).acceleration + ",\t" + tm.getRightTrajectory().get(i).dt); rfw.write("\n"); } diff --git a/Pathgen/src/main/R/drawMP.R b/R scripts/drawMP.R similarity index 96% rename from Pathgen/src/main/R/drawMP.R rename to R scripts/drawMP.R index 1f9870af..42be277e 100644 --- a/Pathgen/src/main/R/drawMP.R +++ b/R scripts/drawMP.R @@ -1,6 +1,6 @@ plotProfile <- function(profileName, inverted = FALSE, wheelbaseDiameter, centerToFront, centerToBack, centerToSide, startY = 0, startPos = c(-1,-1,-1,-1,-1), usePosition = TRUE){ - left <- read.csv(paste("../../../../calciferLeft",profileName,"Profile.csv",sep=""), header=FALSE) - right <- read.csv(paste("../../../../calciferRight",profileName,"Profile.csv",sep=""), header=FALSE) + left <- read.csv(paste("../calciferLeft",profileName,"Profile.csv",sep=""), header=FALSE) + right <- read.csv(paste("../calciferRight",profileName,"Profile.csv",sep=""), header=FALSE) startingCenter <- c(startY, centerToBack) left$V1[1] <- 0 left$V2[1] <- 0 @@ -73,11 +73,11 @@ plotProfile <- function(profileName, inverted = FALSE, wheelbaseDiameter, center #This is the angle for the vector pointing towards the new position of each #wheel. #To understand why this formula is correct, overlay isoclese triangles on the sectors - vectorTheta <- (pi - theta)/2 - (pi/2 - perpendicular) + vectorTheta <- perpendicular+theta/2 #The is the length of the vector pointing towards the new position of each #wheel divided by the radius of the turning circle. - vectorDistanceWithoutR <- sin(theta)/sin((pi-theta)/2) + vectorDistanceWithoutR <- 2*sin(theta/2) #If inverted, swap which wheel gets which input if(inverted){ diff --git a/Pathgen/src/main/R/field.csv b/R scripts/field.csv similarity index 100% rename from Pathgen/src/main/R/field.csv rename to R scripts/field.csv diff --git a/R scripts/findVelVsVoltage.R b/R scripts/findVelVsVoltage.R new file mode 100644 index 00000000..68a8f0fd --- /dev/null +++ b/R scripts/findVelVsVoltage.R @@ -0,0 +1,24 @@ +# Title : findVelVsVoltage +# Objective : Find the line or curve describing how +# Created by: Noah Gleason +# Created on: 9/30/17 + +trials = 1 +voltages = seq(1.5,5,by=0.5) +#voltages = c(0.6, 2, 2.5) +raw <- read.csv("eventLog-2017.10.01.13.58.02.csv") +raw$class <- as.character(raw$class) +maxes <- raw[grep("class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage", raw$class), 3] +maxes <- as.numeric(as.vector(maxes)) + +model <- lm(maxes ~ voltages) +coeffs <- c(coefficients(model)) +View(coeffs) +xInt <- -coeffs[1]/coeffs[2] + +res <- resid(model) + +plot(x=voltages, y=maxes, main = "Max Velocity vs. Voltage", xlab="Voltage (volts)", ylab="Max speed (feet/sec)", xlim=c(0,12), ylim=c(0,12)) +abline(model) +plot(x=voltages, y=res, main="Residuals", xlab="Voltage (volts)", ylab="Residuals (feet/sec)", xlim=c(0,12)) +abline(0,0) \ No newline at end of file diff --git a/R scripts/poseEstimationChecker.R b/R scripts/poseEstimationChecker.R new file mode 100644 index 00000000..68f2782e --- /dev/null +++ b/R scripts/poseEstimationChecker.R @@ -0,0 +1,239 @@ +#Simple helper conversion methods +rad2deg <- function(rad) {(rad * 180) / (pi)} +deg2rad <- function(deg) {(deg * pi) / (180)} + +#Find the distance between the end position of two things +dist <- function(x1, y1, x2, y2){ + return(sqrt((x1[length(x1)] - x2[length(x2)])^2+(y1[length(y1)] - y2[length(y2)])^2)) +} + +#Calculate the effective wheelbase for a given delta left, right, and angle +calcWheelbase <- function(deltaLeft, deltaRight, deltaAngle){ + return((deltaLeft-deltaRight)/deltaAngle); +} + +#Smooths a value while taking its derivative with respect to time. +smoothDerivative <- function(value, timeMillis, n){ + smoothed <- (value[(n+1):length(value)] - value[1:(length(value)-n)])/((timeMillis[(n+1):length(timeMillis)] - timeMillis[1:(length(timeMillis)-n)])/1000); + return(c(rep(0, ceiling(n/2)), smoothed, rep(0, floor(n/2)))); +} + +#Plot the effective wheelbase against a bunch of different things +plotWheelVsVel <- function(leftPos, rightPos, rawAngleDegrees, timeMillis, angularVelThreshRad, smoothingConst){ + #Convert because degrees suuuuck + rawAngle <- deg2rad(rawAngleDegrees) + + #Smooth values and get velocities + angular <- smoothDerivative(rawAngle, timeMillis, smoothingConst) + left <- smoothDerivative(leftPos, timeMillis, smoothingConst) + right <- smoothDerivative(rightPos, timeMillis, smoothingConst) + + #find effective wheelbase + wheelbase <- calcWheelbase(left, right, angular) + + #Filter out low angular vel points + combined <- cbind(angular, wheelbase, (left+right)/2) + combinedAngular <- subset(combined, combined[,1] > angularVelThreshRad) + + #Find the mean wheelbase, weighted by angular vel because higher angular vel decreases variance + avgWheelbase = weighted.mean(x=combinedAngular[,2], w=combinedAngular[,1], na.rm=TRUE) + + #plot wheelbase vs angular vel + plot(x=combinedAngular[,1], y=combinedAngular[,2], xlab="Angular Velocity (rad/sec)", ylab="Effective wheelbase diameter (feet)", main="Effective Wheelbase Diameter vs. Angular Velocity") + abline(a=avgWheelbase, b=0, col='green') + + #plot wheelbase vs linear vel + plot(x=combinedAngular[,3], y=combinedAngular[,2], xlab="Linear Velocity (feet/sec)", ylab="Effective wheelbase diameter (feet)", main="Effective Wheelbase Diameter vs. Linear Velocity") + abline(a=avgWheelbase, b=0, col='green') + + #Plot wheelbase vs turn radius + plot(x=combinedAngular[,3]/combinedAngular[,1], y=combinedAngular[,2]-2.0833, xlab="Turn Radius (feet)", ylab="Error in wheelbase diameter (feet)", main="Error in Wheelbase Diameter vs. Turn Radius") + abline(a=avgWheelbase, b=0, col='green') + + return(avgWheelbase) +} + +#A pose estimation algorithm that assumes the left and right sides have equal scrub, in opposite directions +equalScrubPoseEstimation <- function(leftPos, rightPos, rawAngleDegrees, timeMillis, angularVelThreshRad){ + #Convert because degrees suuuuck + rawAngle <- deg2rad(rawAngleDegrees) + + #Set up output array + out <- array(dim=c(length(timeMillis),8)) + colnames(out)<-c("X","Y","leftX","leftY","rightX","rightY","time","wheelbase") + out[1,] <- c(leftPos[1],rightPos[1],NA,NA,NA,NA,timeMillis[1],NA) + + #Loop through each logged tic, calculating pose iteratively + for(i in 2:length(timeMillis)){ + #Find change in time, in seconds + deltaTime <- (timeMillis[i] - out[i-1,7])/1000 + + #Directly find change in position and angle + deltaLeft <- leftPos[i]-leftPos[i-1] + deltaRight <- rightPos[i]-rightPos[i-1] + deltaTheta <- rawAngle[i]-rawAngle[i-1] + + #Get the effective wheelbase for this iteration + wheelbase <- calcWheelbase(deltaLeft, deltaRight, deltaTheta) + + #Average + avgMoved <- (deltaLeft+deltaRight)/2 + + #The angle of the movement vector + angle <- rawAngle[i-1]+(deltaTheta/2) + + if (deltaTheta == 0){ + #If we're driving straight, we know the magnitude is just the average of the two sides + out[i,] <- c(out[i-1,1]+avgMoved*cos(angle),out[i-1,2]+avgMoved*sin(angle), NA, NA, NA, NA, timeMillis[i],NA) + } else { + #Magnitude of movement vector is 2*r*sin(deltaTheta/2), but r is just avg/deltaTheta + mag <- 2*(avgMoved/deltaTheta)*sin(deltaTheta/2) + + #Vector decomposition + x <- out[i-1,1]+mag*cos(angle) + y <- out[i-1,2]+mag*sin(angle) + + #Only log left and right wheel positions if the angular vel is above threshhold + if (deltaTheta/deltaTime < angularVelThreshRad){ + out[i,] <- c(x, y, NA,NA,NA,NA, timeMillis[i],NA) + } else { + out[i,] <- c(x, y, x+wheelbase/2*cos(rawAngle[i]+pi/2), y+wheelbase/2*sin(rawAngle[i]+pi/2), x+wheelbase/2*cos(rawAngle[i]-pi/2), y+wheelbase/2*sin(rawAngle[i]-pi/2), timeMillis[i],wheelbase) + } + } + } + + #Plot results, with fake wheelbase, only showing points within 1 actual wheelbase of the path + plot(out[,1], out[,2], t="l", xlim = c(min(out[,1], na.rm = TRUE)-3,max(out[,1],na.rm = TRUE)+3), ylim=c(min(out[,2], na.rm = TRUE)-3,max(out[,2], na.rm=TRUE)+3), xlab="X position (Feet)", ylab="Y position (Feet)", main="Equal Scrub Pose Estimation Algorithm", asp=1) + lines(out[,3], out[,4], col="Green") + lines(out[,5], out[,6], col="Red") + + return(out) +} + +#A pose estimation algorithm that ignores the worse encoder reading. +ignoreWorstPoseEstimation <- function(leftPos, rightPos, rawAngleDegrees, timeMillis, actualWheelbase){ + #Convert because degrees suuuuck + rawAngle <- deg2rad(rawAngleDegrees) + + #Set up output array + out <- array(dim=c(length(timeMillis),7)) + colnames(out) <- c("X","Y","leftX","leftY","rightX","rightY","time") + angle <- rawAngle[1] + out[1,] <- c(leftPos[1],rightPos[1],actualWheelbase/2*cos(angle+pi/2), actualWheelbase/2*sin(angle+pi/2), actualWheelbase/2*cos(angle-pi/2), actualWheelbase/2*sin(angle-pi/2),timeMillis[1]) + + #Loop through each logged tic, calculating pose iteratively + for(i in 2:length(timeMillis)){ + + #Directly find change in position and angle + deltaLeft <- leftPos[i]-leftPos[i-1] + deltaRight <- rightPos[i]-rightPos[i-1] + deltaTheta <- rawAngle[i]-rawAngle[i-1] + + #The angle of the movement vector + angle <- rawAngle[i-1]+(deltaTheta/2) + + #Take the side that slipped more and recalculate it from the wheelbase, change in angle, and other side's change + if (deltaTheta < (deltaLeft - deltaRight) / actualWheelbase) { + if (deltaLeft > 0) { + deltaLeft = deltaRight + actualWheelbase * deltaTheta; + } else { + deltaRight = deltaLeft - actualWheelbase * deltaTheta; + } + } else if (deltaTheta > (deltaLeft - deltaRight) / actualWheelbase) { + if (deltaLeft < 0) { + deltaLeft = deltaRight + actualWheelbase * deltaTheta; + } else { + deltaRight = deltaLeft - actualWheelbase * deltaTheta; + } + } + + #Calculate average after recalculating one of the sides + avgMoved <- (deltaLeft+deltaRight)/2 + + #If we're driving straight, the magnitude is just the average of the two sides + if (deltaTheta == 0){ + out[i,] <- c(out[i-1,1]+avgMoved*cos(angle),out[i-1,2]+avgMoved*sin(angle), x+actualWheelbase/2*cos(angle+pi/2), y+actualWheelbase/2*sin(angle+pi/2), x+actualWheelbase/2*cos(angle-pi/2), y+actualWheelbase/2*sin(angle-pi/2), timeMillis[i]) + } else { + #If the sides moved the same distance but the angle changed, the radius is just the sector length over the angle + if (deltaLeft-deltaRight == 0){ + r <- avgMoved/deltaTheta; + } else { + #If they moved a different distance, do a more complicated equation (may be the same as the other one, not doing the math yet) + r <- actualWheelbase / 2. * (deltaLeft + deltaRight) / (deltaLeft - deltaRight); + } + mag <- 2. * r * sin(deltaTheta / 2.); + + #Vector decomposition + x <- out[i-1,1]+mag*cos(angle) + y <- out[i-1,2]+mag*sin(angle) + out[i,] <- c(x, y, x+actualWheelbase/2*cos(rawAngle[i]+pi/2), y+actualWheelbase/2*sin(rawAngle[i]+pi/2), x+actualWheelbase/2*cos(rawAngle[i]-pi/2), y+actualWheelbase/2*sin(rawAngle[i]-pi/2), timeMillis[i]) + } + } + + #Plot results, with real wheelbase + plot(out[,1], out[,2], t="l", xlim = c(min(out[,1], out[,3], out[,5]),max(out[,1], out[,3], out[,5])), ylim=c(min(out[,2], out[,4], out[,6]),max(out[,2], out[,4], out[,6])), xlab="X position (Feet)", ylab="Y position (Feet)", main="Ignore-Worst Pose Estimation Algorithm",asp=1) + lines(out[,3], out[,4], col="Green") + lines(out[,5], out[,6], col="Red") + + return(out) +} + +#A pose estimation algorithm that only uses the encoders +encoderOnlyPoseEstimation <- function(leftPos, rightPos, startingAngleDegrees, timeMillis, fakeWheelbase){ + #Convert because degrees suuuuck + startingAngle <- deg2rad(startingAngleDegrees) + + wheelRadius <- fakeWheelbase/2 + + #Set up output array + out <- array(dim=c(length(timeMillis), 8)) + colnames(out) <- c("X","Y","leftX","leftY","rightX","rightY","angle","time") + out[1,] <- c(leftPos[1],rightPos[1],wheelRadius*cos(startingAngle+pi/2), wheelRadius*sin(startingAngle+pi/2), wheelRadius*cos(startingAngle-pi/2), wheelRadius*sin(startingAngle-pi/2),startingAngle,timeMillis[1]) + + #Loop through each logged tic, calculating pose iteratively + for(i in 2:length(timeMillis)){ + + #Directly find change in position and angle + deltaLeft <- leftPos[i]-leftPos[i-1] + deltaRight <- rightPos[i]-rightPos[i-1] + + #Average + avgMoved <- (deltaLeft+deltaRight)/2 + + #Points in the direction the robot is facing at the start of tic + perpendicular <- out[i-1,7] + + #The angle of the sector the path is tracing + theta <- (deltaLeft - deltaRight)/fakeWheelbase + + #If not turning, magnitude is just the average moved + if(theta == 0){ + mag <- avgMoved + } else { + #If turning, calculate the radius and use that to get the magnitude of the turn + mag <- 2*(avgMoved/theta)*sin(theta/2) + } + + angle <- perpendicular + (theta/2) + x <- out[i-1,1]+mag*cos(angle) + y <- out[i-1,2]+mag*sin(angle) + newHeading <- perpendicular + theta + out[i,] <- c(x,y,x+wheelRadius*cos(newHeading+pi/2), y+wheelRadius*sin(newHeading+pi/2), x+wheelRadius*cos(newHeading-pi/2), y+wheelRadius*sin(newHeading-pi/2), newHeading, timeMillis[i]) + } + + #Plot results, with fake wheelbase + plot(out[,1], out[,2], t="l", xlim = c(min(out[,1], out[,3], out[,5]),max(out[,1], out[,3], out[,5])), ylim=c(min(out[,2], out[,4], out[,6]),max(out[,2], out[,4], out[,6])), xlab="X position (Feet)", ylab="Y position (Feet)", main="Encoder-only Pose Estimation Algorithm",asp=1) + lines(out[,3], out[,4], col="Green") + lines(out[,5], out[,6], col="Red") + + return(out) +} + +#Make all the graphs, for wheelbase and all 3 algorithms, using the average effective wheelbase for encoder-only +doEverything <- function(leftPos, rightPos, rawAngleDegrees, timeMillis, angularVelThreshRad, smoothingConst, actualWheelbase){ + avg <- plotWheelVsVel(leftPos, rightPos, rawAngleDegrees, timeMillis, angularVelThreshRad, smoothingConst) + equalScrubPoseEstimation(leftPos, rightPos, rawAngleDegrees, timeMillis, angularVelThreshRad) + ignoreWorstPoseEstimation(leftPos, rightPos, rawAngleDegrees, timeMillis, actualWheelbase) + encoderOnlyPoseEstimation(leftPos=leftPos, rightPos=rightPos, startingAngleDegrees=rawAngleDegrees[1], timeMillis=timeMillis, fakeWheelbase=avg) + return(avg) +} \ No newline at end of file diff --git a/Pathgen/src/main/R/robot.csv b/R scripts/robot.csv similarity index 100% rename from Pathgen/src/main/R/robot.csv rename to R scripts/robot.csv diff --git a/README.md b/README.md index 8c4cd472..ecb402bc 100644 --- a/README.md +++ b/README.md @@ -17,3 +17,5 @@ For info on our framework, see [here](http://team449.shoutwiki.com/wiki/Informat Reading everything [here](http://team449.shoutwiki.com/wiki/Category:Programming) before writing code is probably a good idea. + +MRA Education Day presentation: https://docs.google.com/presentation/d/1PWEmE_5zcDg5OGz8K20IKFjoHMwizs2ychw535TPyaI/edit?usp=sharing diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java index db669889..893a1146 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/Robot.java @@ -70,6 +70,11 @@ public class Robot extends IterativeRobot { @Nullable private Command autonomousCommand; + /** + * Whether or not the robot has been enabled yet. + */ + private boolean enabled; + /** * The method that runs when the robot is turned on. Initializes all subsystems from the map. */ @@ -78,14 +83,17 @@ public void robotInit() { Clock.setStartTime(); Clock.updateTime(); + enabled = false; + //Yes this should be a print statement, it's useful to know that robotInit started. System.out.println("Started robotInit."); Yaml yaml = new Yaml(); try { //Read the yaml file with SnakeYaml so we can use anchors and merge syntax. -// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "ballbasaur_map.yml")); - Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "calcifer_map.yml")); +// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH+"ballbasaur_map.yml")); + Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "naveen_map.yml")); +// Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "nate_map.yml")); // Map normalized = (Map) yaml.load(new FileReader(RESOURCES_PATH + "calcifer_outreach_map.yml")); YAMLMapper mapper = new YAMLMapper(); //Turn the Map read by SnakeYaml into a String so Jackson can read it. @@ -99,6 +107,10 @@ public void robotInit() { System.out.println("Config file is bad/nonexistent!"); e.printStackTrace(); } + + //Read sensors + this.robotMap.getUpdater().run(); + //Set fields from the map. this.loggerNotifier = new Notifier(robotMap.getLogger()); this.driveSubsystem = robotMap.getDrive(); @@ -163,6 +175,7 @@ public void robotInit() { //Run the logger to write all the events that happened during initialization to a file. robotMap.getLogger().run(); + Clock.updateTime(); } /** @@ -171,8 +184,21 @@ public void robotInit() { @Override public void teleopInit() { //Do the startup tasks - driveSubsystem.stopMPProcesses(); doStartupTasks(); + + //Read sensors + this.robotMap.getUpdater().run(); + + //Run startup command if we start in teleop. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + + driveSubsystem.stopMPProcesses(); + if (robotMap.getTeleopStartupCommand() != null) { robotMap.getTeleopStartupCommand().start(); } @@ -191,6 +217,10 @@ public void teleopInit() { public void teleopPeriodic() { //Refresh the current time. Clock.updateTime(); + + //Read sensors + this.robotMap.getUpdater().run(); + //Run all commands. This is a WPILib thing you don't really have to worry about. Scheduler.getInstance().run(); } @@ -202,6 +232,18 @@ public void teleopPeriodic() { public void autonomousInit() { //Do startup tasks doStartupTasks(); + + //Read sensors + this.robotMap.getUpdater().run(); + + //Run startup command if we start in auto. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + if (robotMap.getAutoStartupCommand() != null) { robotMap.getAutoStartupCommand().start(); } @@ -222,6 +264,8 @@ public void autonomousInit() { public void autonomousPeriodic() { //Update the current time Clock.updateTime(); + //Read sensors + this.robotMap.getUpdater().run(); //Run all commands. This is a WPILib thing you don't really have to worry about. Scheduler.getInstance().run(); } @@ -237,6 +281,30 @@ public void disabledInit() { sendModeOverI2C(robotInfo, "disabled"); } + /** + * Run when we first enable in test mode. + */ + @Override + public void testInit() { + //Run startup command if we start in test mode. + if (!enabled) { + if (robotMap.getStartupCommand() != null) { + robotMap.getStartupCommand().start(); + } + enabled = true; + } + } + + /** + * Run every tic while disabled + */ + @Override + public void disabledPeriodic() { + Clock.updateTime(); + //Read sensors + this.robotMap.getUpdater().run(); + } + /** * Sends the current mode (auto, teleop, or disabled) over I2C. * @@ -267,9 +335,5 @@ private void doStartupTasks() { //Start running the logger loggerNotifier.startPeriodic(robotMap.getLogger().getLoopTimeSecs()); - - //Enable and reset the drive - driveSubsystem.enableMotors(); - driveSubsystem.resetPosition(); } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap2017.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap2017.java index 601eced4..0046a2b7 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap2017.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/RobotMap2017.java @@ -7,6 +7,7 @@ import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedDigitalInput; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommand; import org.usfirst.frc.team449.robot.oi.OI; import org.usfirst.frc.team449.robot.oi.buttons.CommandButton; @@ -19,6 +20,7 @@ import org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork; import org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics; +import java.util.ArrayList; import java.util.List; import java.util.Map; @@ -57,6 +59,12 @@ public class RobotMap2017 { @NotNull private final Command defaultDriveCommand; + /** + * A runnable that updates cached variables. + */ + @NotNull + private final Runnable updater; + /** * The climber for boarding the airship. Can be null. */ @@ -190,6 +198,12 @@ public class RobotMap2017 { @Nullable private final Command teleopStartupCommand; + /** + * The command to be run when first enabled. + */ + @Nullable + private final Command startupCommand; + /** * Whether to run the test or real motion profile during autonomous. */ @@ -203,53 +217,56 @@ public class RobotMap2017 { /** * Default constructor. * - * @param buttons The buttons for controlling this robot. - * @param oi The OI for controlling this robot's drive. - * @param logger The logger for recording events and telemetry data. - * @param drive The drive. - * @param defaultDriveCommand The command for the drive to run during the teleoperated period. - * @param climber The climber for boarding the airship. Can be null. - * @param shooter The multiSubsystem for shooting fuel. Can be null. - * @param camera The cameras on this robot. Can be null. - * @param intake The intake for picking up and agitating balls. Can be null. - * @param pneumatics The pneumatics on this robot. Can be null. - * @param gearHandler The gear handler on this robot. Can be null. - * @param RIOduinoPort The I2C port of the RIOduino plugged into this robot. Can be null. - * @param allianceSwitch The switch for selecting which alliance we're on. Can be null if doMP is false or - * testMP is true, but otherwise must have a value. - * @param dropGearSwitch The switch for deciding whether or not to drop the gear. Can be null if doMP is false - * or testMP is true, but otherwise must have a value. - * @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP is - * false or testMP is true, but otherwise must have a value. - * @param boilerAuto The command to run in autonomous on the boiler side of the field. Can be null if doMP - * is false or testMP is true, but otherwise must have a value. - * @param centerAuto The command to run in autonomous on the center of the field. Can be null if doMP is - * false or testMP is true, but otherwise must have a value. - * @param feederAuto The command to run in autonomous on the feeding station side of the field. Can be null - * if doMP is false or testMP is true, but otherwise must have a value. - * @param leftTestProfile The profile for the left side of the drive to run in test mode. Can be null if either - * testMP or doMP are false, but otherwise must have a value. - * @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if either - * testMP or doMP are false, but otherwise must have a value. - * @param leftProfiles The starting position to peg profiles for the left side. Should have options for - * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". - * Can be null if doMP is false or testMP is true, but otherwise must have a value. - * @param rightProfiles The starting position to peg profiles for the right side. Should have options for - * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". - * Can be null if doMP is false or testMP is true, but otherwise must have a value. - * @param nonMPAutoCommand The command to run during autonomous if doMP is false. Can be null, and if it is, no - * command is run during autonomous. - * @param autoStartupCommand The command to be run when first enabled in autonomous mode. - * @param teleopStartupCommand The command to be run when first enabled in teleoperated mode. - * @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false. - * @param doMP Whether to run a motion profile during autonomous. Defaults to true. + * @param buttons The buttons for controlling this robot. Can be null for an empty list. + * @param oi The OI for controlling this robot's drive. + * @param logger The logger for recording events and telemetry data. + * @param drive The drive. + * @param defaultDriveCommand The command for the drive to run during the teleoperated period. + * @param updater A runnable that updates cached variables. + * @param climber The climber for boarding the airship. Can be null. + * @param shooter The multiSubsystem for shooting fuel. Can be null. + * @param camera The cameras on this robot. Can be null. + * @param intake The intake for picking up and agitating balls. Can be null. + * @param pneumatics The pneumatics on this robot. Can be null. + * @param gearHandler The gear handler on this robot. Can be null. + * @param RIOduinoPort The I2C port of the RIOduino plugged into this robot. Can be null. + * @param allianceSwitch The switch for selecting which alliance we're on. Can be null if doMP is false or + * testMP is true, but otherwise must have a value. + * @param dropGearSwitch The switch for deciding whether or not to drop the gear. Can be null if doMP is false + * or testMP is true, but otherwise must have a value. + * @param locationDial The dial for selecting which side of the field the robot is on. Can be null if doMP + * is false or testMP is true, but otherwise must have a value. + * @param boilerAuto The command to run in autonomous on the boiler side of the field. Can be null if doMP + * is false or testMP is true, but otherwise must have a value. + * @param centerAuto The command to run in autonomous on the center of the field. Can be null if doMP is + * false or testMP is true, but otherwise must have a value. + * @param feederAuto The command to run in autonomous on the feeding station side of the field. Can be + * null if doMP is false or testMP is true, but otherwise must have a value. + * @param leftTestProfile The profile for the left side of the drive to run in test mode. Can be null if either + * testMP or doMP are false, but otherwise must have a value. + * @param rightTestProfile The profile for the right side of the drive to run in test mode. Can be null if + * either testMP or doMP are false, but otherwise must have a value. + * @param leftProfiles The starting position to peg profiles for the left side. Should have options for + * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + * Can be null if doMP is false or testMP is true, but otherwise must have a value. + * @param rightProfiles The starting position to peg profiles for the right side. Should have options for + * "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + * Can be null if doMP is false or testMP is true, but otherwise must have a value. + * @param nonMPAutoCommand The command to run during autonomous if doMP is false. Can be null, and if it is, no + * command is run during autonomous. + * @param autoStartupCommand The command to be run when first enabled in autonomous mode. + * @param teleopStartupCommand The command to be run when first enabled in teleoperated mode. + * @param startupCommand The command to be run when first enabled. + * @param testMP Whether to run the test or real motion profile during autonomous. Defaults to false. + * @param doMP Whether to run a motion profile during autonomous. Defaults to true. */ @JsonCreator - public RobotMap2017(@NotNull @JsonProperty(required = true) List buttons, + public RobotMap2017(@Nullable @JsonProperty(required = true) List buttons, @NotNull @JsonProperty(required = true) OI oi, @NotNull @JsonProperty(required = true) Logger logger, @NotNull @JsonProperty(required = true) DriveTalonCluster drive, @NotNull @JsonProperty(required = true) YamlCommand defaultDriveCommand, + @NotNull @JsonProperty(required = true) MappedRunnable updater, @Nullable ClimberCurrentLimited climber, @Nullable LoggingShooter shooter, @Nullable CameraNetwork camera, @@ -268,9 +285,10 @@ public RobotMap2017(@NotNull @JsonProperty(required = true) List @Nullable YamlCommand nonMPAutoCommand, @Nullable YamlCommand autoStartupCommand, @Nullable YamlCommand teleopStartupCommand, + @Nullable YamlCommand startupCommand, boolean testMP, @Nullable Boolean doMP) { - this.buttons = buttons; + this.buttons = buttons != null ? buttons : new ArrayList<>(); this.oi = oi; this.drive = drive; this.climber = climber; @@ -280,6 +298,7 @@ public RobotMap2017(@NotNull @JsonProperty(required = true) List this.pneumatics = pneumatics; this.gearHandler = gearHandler; this.logger = logger; + this.updater = updater; this.RIOduinoPort = RIOduinoPort; this.allianceSwitch = allianceSwitch; this.dropGearSwitch = dropGearSwitch; @@ -295,6 +314,7 @@ public RobotMap2017(@NotNull @JsonProperty(required = true) List this.nonMPAutoCommand = nonMPAutoCommand != null ? nonMPAutoCommand.getCommand() : null; this.autoStartupCommand = autoStartupCommand != null ? autoStartupCommand.getCommand() : null; this.teleopStartupCommand = teleopStartupCommand != null ? teleopStartupCommand.getCommand() : null; + this.startupCommand = startupCommand != null ? startupCommand.getCommand() : null; this.testMP = testMP; this.doMP = doMP != null ? doMP : true; } @@ -524,4 +544,20 @@ public Command getTeleopStartupCommand() { public boolean getDoMP() { return doMP; } + + /** + * @return The command to be run when first enabled. + */ + @Nullable + public Command getStartupCommand() { + return startupCommand; + } + + /** + * @return A runnable that updates cached variables. + */ + @NotNull + public Runnable getUpdater() { + return updater; + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.java index b01bdf64..3fdd8d41 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.java @@ -14,7 +14,7 @@ * A command group for running many commands in parallel. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class ParallelCommandGroup extends YamlCommandGroupWrapper{ +public class ParallelCommandGroup extends YamlCommandGroupWrapper { /** * Default constructor diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/RunRunnables.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/RunRunnables.java new file mode 100644 index 00000000..fdc06af8 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/general/RunRunnables.java @@ -0,0 +1,76 @@ +package org.usfirst.frc.team449.robot.commands.general; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandWrapper; +import org.usfirst.frc.team449.robot.other.Logger; + +/** + * A command that runs any number of {@link Runnable} objects every tic. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class RunRunnables extends YamlCommandWrapper { + + /** + * The runnables to run. + */ + @NotNull + private final Runnable[] runnables; + + /** + * Default constructor + * + * @param runnables The runnables to run. + */ + @JsonCreator + public RunRunnables(@NotNull @JsonProperty(required = true) MappedRunnable[] runnables) { + this.runnables = runnables; + } + + /** + * Log on init + */ + @Override + protected void initialize() { + Logger.addEvent("RunRunnables init.", this.getClass()); + } + + /** + * Run all the runnables in the order they were given. + */ + @Override + protected void execute() { + for (Runnable runnable : runnables) { + runnable.run(); + } + } + + /** + * @return false + */ + @Override + protected boolean isFinished() { + //This does NOT have to be true. + return false; + } + + /** + * Log on exit. + */ + @Override + protected void end() { + Logger.addEvent("RunRunnables end.", this.getClass()); + } + + /** + * Log when interrupted. + */ + @Override + protected void interrupted() { + Logger.addEvent("RunRunnables Interrupted!", this.getClass()); + } +} \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/RunMotorWhileConditonMet.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/RunMotorWhileConditonMet.java index dc5c3369..a22ecf58 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/RunMotorWhileConditonMet.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/RunMotorWhileConditonMet.java @@ -15,7 +15,7 @@ * Run a BinaryMotor while a condition is true. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class RunMotorWhileConditonMet extends YamlCommandWrapper { +public class RunMotorWhileConditonMet extends YamlCommandWrapper { /** * The subsystem to execute this command on @@ -57,7 +57,7 @@ protected void execute() { */ @Override protected boolean isFinished() { - return subsystem.isConditionTrue(); + return subsystem.isConditionTrueCached(); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommand.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommand.java index 0eb3087d..eebf9d98 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommand.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommand.java @@ -8,7 +8,7 @@ import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; import org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOriented; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand; import java.util.ArrayList; @@ -19,7 +19,7 @@ */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class FieldOrientedUnidirectionalDriveCommand extends PIDAngleCommand { +public class FieldOrientedUnidirectionalDriveCommand extends PIDAngleCommand { /** * The drive this command is controlling. @@ -159,7 +159,7 @@ protected void interrupted() { protected void usePIDOutput(double output) { SmartDashboard.putNumber("Unprocessed loop output", output); //Process or zero the input depending on whether the NavX is being overriden. - output = subsystem.getOverrideNavX() ? 0 : processPIDOutput(output); + output = subsystem.getOverrideGyro() ? 0 : processPIDOutput(output); SmartDashboard.putNumber("PID loop output", output); diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommandShifting.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommandShifting.java index c1842b66..f5af6ea2 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommandShifting.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/FieldOrientedUnidirectionalDriveCommandShifting.java @@ -10,7 +10,7 @@ import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; import org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOriented; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; import java.util.List; @@ -19,7 +19,7 @@ */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class FieldOrientedUnidirectionalDriveCommandShifting +public class FieldOrientedUnidirectionalDriveCommandShifting extends FieldOrientedUnidirectionalDriveCommand { /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/JiggleRobot.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/JiggleRobot.java index c98d384d..196b82a0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/JiggleRobot.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/JiggleRobot.java @@ -9,13 +9,13 @@ import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandGroupWrapper; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * Rotates the robot back and forth in order to dislodge any stuck balls. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class JiggleRobot extends YamlCommandGroupWrapper { +public class JiggleRobot extends YamlCommandGroupWrapper { /** * Instantiate the CommandGroup diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXDriveStraight.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXDriveStraight.java index 866026c4..777ac6d0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXDriveStraight.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXDriveStraight.java @@ -10,14 +10,14 @@ import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; import org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand; /** * Drives straight using the NavX gyro to keep a constant alignment. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class NavXDriveStraight extends PIDAngleCommand { +public class NavXDriveStraight extends PIDAngleCommand { /** * The drive subsystem to give output to. @@ -87,15 +87,11 @@ protected void usePIDOutput(double output) { output = processPIDOutput(output); //Set throttle to the specified stick. - double throttle; if (useLeft) { - throttle = oi.getLeftThrottle(); + subsystem.setOutput(oi.getLeftOutputCached() - output, oi.getLeftOutputCached() + output); } else { - throttle = oi.getRightThrottle(); + subsystem.setOutput(oi.getRightOutputCached() - output, oi.getRightOutputCached() + output); } - - //Set the output to the throttle velocity adjusted by the PID output. - subsystem.setOutput(throttle - output, throttle + output); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngle.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngle.java index 98e6ef77..98a8b7b5 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngle.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngle.java @@ -11,14 +11,14 @@ import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; import org.usfirst.frc.team449.robot.other.Clock; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand; /** * Turns to a specified angle, relative to the angle the navX was at when the robot was turned on. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class NavXTurnToAngle extends PIDAngleCommand { +public class NavXTurnToAngle extends PIDAngleCommand { /** * The drive subsystem to execute this command on and to get the gyro reading from. diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngleRelative.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngleRelative.java index 08d80fb4..f397aa20 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngleRelative.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/NavXTurnToAngleRelative.java @@ -10,13 +10,13 @@ import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; import org.usfirst.frc.team449.robot.other.Clock; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * Turn a certain number of degrees from the current heading. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class NavXTurnToAngleRelative extends NavXTurnToAngle { +public class NavXTurnToAngleRelative extends NavXTurnToAngle { /** * Default constructor. @@ -62,7 +62,7 @@ protected void initialize() { this.startTime = Clock.currentTimeMillis(); Logger.addEvent("NavXRelativeTurnToAngle init.", this.getClass()); //Do math to setup the setpoint. - this.setSetpoint(clipTo180(((SubsystemNavX) subsystem).getGyroOutput() + setpoint)); + this.setSetpoint(clipTo180(((SubsystemAHRS) subsystem).getHeadingCached() + setpoint)); //Make sure to enable the controller! this.getPIDController().enable(); } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXDefaultDrive.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXDefaultDrive.java index 4dcff1b6..67a8ad40 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXDefaultDrive.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXDefaultDrive.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team449.robot.commands.multiInterface.drive; import com.fasterxml.jackson.annotation.*; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import org.jetbrains.annotations.NotNull; import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional; @@ -8,7 +9,7 @@ import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional; import org.usfirst.frc.team449.robot.other.BufferTimer; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand; /** @@ -16,7 +17,7 @@ */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class UnidirectionalNavXDefaultDrive extends PIDAngleCommand { +public class UnidirectionalNavXDefaultDrive extends PIDAngleCommand { /** * The drive this command is controlling. @@ -116,22 +117,20 @@ protected void initialize() { */ @Override protected void execute() { - //Check whether we're commanding to drive straight or turn. - boolean commandingStraight = oi.commandingStraight(); - + SmartDashboard.putBoolean("Override",subsystem.getOverrideGyro()); //If we're driving straight but the driver tries to turn or overrides the navX: - if (drivingStraight && (!commandingStraight || subsystem.getOverrideNavX())) { + if (drivingStraight && (!oi.commandingStraightCached() || subsystem.getOverrideGyro())) { //Switch to free drive drivingStraight = false; } //If we're free driving and the driver stops turning: - else if (driveStraightLoopEntryTimer.get(!(subsystem.getOverrideNavX()) && !(drivingStraight) && - commandingStraight && Math.abs(subsystem.getNavX().getRate()) <= maxAngularVelToEnterLoop)) { + else if (driveStraightLoopEntryTimer.get(!(subsystem.getOverrideGyro()) && !(drivingStraight) && + oi.commandingStraightCached() && Math.abs(subsystem.getAngularVelCached()) <= maxAngularVelToEnterLoop)) { //Switch to driving straight drivingStraight = true; //Set the setpoint to the current heading and reset the navX this.getPIDController().reset(); - this.getPIDController().setSetpoint(subsystem.getGyroOutput()); + this.getPIDController().setSetpoint(subsystem.getHeadingCached()); this.getPIDController().enable(); } } @@ -170,23 +169,24 @@ protected void interrupted() { */ @Override protected void usePIDOutput(double output) { + SmartDashboard.putBoolean("Driving straight", drivingStraight); //If we're driving straight.. if (drivingStraight) { //Process the output (minimumOutput, deadband, etc.) output = processPIDOutput(output); //Deadband if we're stationary - if(oi.getLeftOutput() == 0 || oi.getRightOutput() == 0){ - output=deadbandOutput(output); + if (oi.getLeftOutputCached() == 0 || oi.getRightOutputCached() == 0) { + output = deadbandOutput(output); } //Adjust the heading according to the PID output, it'll be positive if we want to go right. - subsystem.setOutput(oi.getLeftOutput() - output, oi.getRightOutput() + output); + subsystem.setOutput(oi.getLeftOutputCached() - output, oi.getRightOutputCached() + output); } //If we're free driving... else { //Set the throttle to normal arcade throttle. - subsystem.setOutput(oi.getLeftOutput(), oi.getRightOutput()); + subsystem.setOutput(oi.getLeftOutputCached(), oi.getRightOutputCached()); } } } \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXShiftingDefaultDrive.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXShiftingDefaultDrive.java index bc6b508b..a9ce3710 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXShiftingDefaultDrive.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiInterface/drive/UnidirectionalNavXShiftingDefaultDrive.java @@ -11,7 +11,7 @@ import org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional; import org.usfirst.frc.team449.robot.other.BufferTimer; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * Drive with arcade drive setup, autoshift, and when the driver isn't turning, use a NavX to stabilize the robot's @@ -19,7 +19,7 @@ */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class UnidirectionalNavXShiftingDefaultDrive extends UnidirectionalNavXDefaultDrive { +public class UnidirectionalNavXShiftingDefaultDrive extends UnidirectionalNavXDefaultDrive { /** * The drive to execute this command on. @@ -61,7 +61,7 @@ public class UnidirectionalNavXShiftingDefaultDrive subsystem.setGear(gear)); + autoshiftComponent.autoshift((oi.getLeftOutputCached() + oi.getRightOutputCached())/2., subsystem.getLeftVelCached(), + subsystem.getRightVelCached(), gear -> subsystem.setGear(gear)); } super.execute(); } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/LoadShooter.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/LoadShooter.java index fc5f5f48..b6c207d4 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/LoadShooter.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/LoadShooter.java @@ -17,7 +17,7 @@ * intake, and stops feeder. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class LoadShooter extends YamlCommandGroupWrapper { +public class LoadShooter extends YamlCommandGroupWrapper { /** * Constructs a LoadShooter command group diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/RackShooter.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/RackShooter.java index d0a14c54..666222e0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/RackShooter.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/RackShooter.java @@ -17,7 +17,7 @@ * intake, and stops feeder. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class RackShooter extends YamlCommandGroupWrapper { +public class RackShooter extends YamlCommandGroupWrapper { /** * Constructs a RackShooter command group diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/ResetShooter.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/ResetShooter.java index 83f631a4..bf931faf 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/ResetShooter.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/commands/multiSubsystem/ResetShooter.java @@ -16,7 +16,7 @@ * Command group to reset everything. Turns everything off, raises intake */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class ResetShooter extends YamlCommandGroupWrapper { +public class ResetShooter extends YamlCommandGroupWrapper { /** * Constructs a ResetShooter command group diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/AutoshiftComponent.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/AutoshiftComponent.java index 9e185a55..f7043245 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/AutoshiftComponent.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/AutoshiftComponent.java @@ -59,6 +59,11 @@ public class AutoshiftComponent { */ private long timeLastDownshifted; + /** + * Whether it's okay to up or down shift. Fields to avoid garbage collection. + */ + private boolean okayToUpshift, okayToDownshift; + /** * Default constructor * @@ -100,23 +105,23 @@ public AutoshiftComponent(@JsonProperty(required = true) double upshiftSpeed, */ private boolean shouldDownshift(double forwardThrottle, double leftVel, double rightVel) { //We should shift if we're going slower than the downshift speed - boolean okToShift = Math.max(Math.abs(leftVel), Math.abs(rightVel)) < downshiftSpeed; + okayToDownshift = Math.max(Math.abs(leftVel), Math.abs(rightVel)) < downshiftSpeed; //Or if we're just turning in place. - okToShift = okToShift || (forwardThrottle == 0); + okayToDownshift = okayToDownshift || (forwardThrottle == 0); //Or commanding a low speed. - okToShift = okToShift || (Math.abs(forwardThrottle) < upshiftFwdThresh); + okayToDownshift = okayToDownshift || (Math.abs(forwardThrottle) < upshiftFwdThresh); //But we can only shift if we're out of the cooldown period. - okToShift = okToShift && Clock.currentTimeMillis() - timeLastUpshifted > cooldownAfterUpshift; + okayToDownshift = okayToDownshift && Clock.currentTimeMillis() - timeLastUpshifted > cooldownAfterUpshift; //We use a BufferTimer so we only shift if the conditions are met for a specific continuous interval. // This avoids brief blips causing shifting. - okToShift = downshiftBufferTimer.get(okToShift); + okayToDownshift = downshiftBufferTimer.get(okayToDownshift); //Record the time if we do decide to shift. - if (okToShift) { + if (okayToDownshift) { timeLastDownshifted = Clock.currentTimeMillis(); } - return okToShift; + return okayToDownshift; } /** @@ -129,19 +134,19 @@ private boolean shouldDownshift(double forwardThrottle, double leftVel, double r */ private boolean shouldUpshift(double forwardThrottle, double leftVel, double rightVel) { //We should shift if we're going faster than the upshift speed... - boolean okToShift = Math.min(Math.abs(leftVel), Math.abs(rightVel)) > upshiftSpeed; + okayToUpshift = Math.min(Math.abs(leftVel), Math.abs(rightVel)) > upshiftSpeed; //AND the driver's trying to go forward fast. - okToShift = okToShift && Math.abs(forwardThrottle) > upshiftFwdThresh; + okayToUpshift = okayToUpshift && Math.abs(forwardThrottle) > upshiftFwdThresh; //But we can only shift if we're out of the cooldown period. - okToShift = okToShift && Clock.currentTimeMillis() - timeLastDownshifted > cooldownAfterDownshift; + okayToUpshift = okayToUpshift && Clock.currentTimeMillis() - timeLastDownshifted > cooldownAfterDownshift; //We use a BufferTimer so we only shift if the conditions are met for a specific continuous interval. // This avoids brief blips causing shifting. - okToShift = upshiftBufferTimer.get(okToShift); - if (okToShift) { + okayToUpshift = upshiftBufferTimer.get(okayToUpshift); + if (okayToUpshift) { timeLastUpshifted = Clock.currentTimeMillis(); } - return okToShift; + return okayToUpshift; } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/NavXRumbleComponent.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/NavXRumbleComponent.java new file mode 100644 index 00000000..e206f462 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/NavXRumbleComponent.java @@ -0,0 +1,152 @@ +package org.usfirst.frc.team449.robot.components; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import com.kauailabs.navx.frc.AHRS; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.generalInterfaces.rumbleable.Rumbleable; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedAHRS; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; +import org.usfirst.frc.team449.robot.other.Clock; + +import java.util.List; + +/** + * A component to rumble controllers based off the jerk measurements from a NavX. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class NavXRumbleComponent implements MappedRunnable { + + /** + * The factor to multiply feet/(sec^3) by to get Gs/millisecond, according to WolframAlpha. + */ + private static final double FPS_CUBED_TO_GS_PER_MILLIS = 3.108e-5; + + /** + * The NavX to get jerk measurements from. + */ + @NotNull + private final AHRS navX; + + /** + * The things to rumble. + */ + @NotNull + private final List rumbleables; + + /** + * The minimum jerk that will trigger rumbling, in Gs/millisecond. Should be greater than 2, which is the error + * margin on the measurement. + */ + private final double minJerk; + + /** + * The jerk, in Gs/millisecond, that's scaled to maximum rumble. All jerks of greater magnitude are capped at 1. + */ + private final double maxJerk; + + /** + * Whether the NavX Y-axis measures forwards-back jerk or left-right jerk. + */ + private final boolean yIsFrontBack; + + /** + * Whether to invert the left-right jerk measurement. + */ + private final boolean invertLeftRight; + + /** + * Variables for the per-call rumble calculation representing the directional accelerations. Fields to avoid garbage + * collection. + */ + private double lastFrontBackAccel, lastLeftRightAccel; + + /** + * Variables for the per-call rumble calculation representing the rumble outputs. Fields to avoid garbage + * collection. + */ + private double left, right; + + /** + * Variables for per-call acceleration calculation. Fields to avoid garbage collection. + */ + private double frontBack, leftRight; + + /** + * The time at which the acceleration was last measured. + */ + private long timeLastCalled; + + /** + * Default constructor. + * + * @param navX The NavX to get jerk measurements from. + * @param rumbleables The things to rumble. + * @param minJerk The minimum jerk that will trigger rumbling, in feet/(sec^3). + * @param maxJerk The jerk, in feet/(sec^3), that's scaled to maximum rumble. All jerks of greater magnitude + * are capped at 1. + * @param yIsFrontBack Whether the NavX Y-axis measures forwards-back jerk or left-right jerk. Defaults to + * false. + * @param invertLeftRight Whether to invert the left-right jerk measurement. Defaults to false. + */ + @JsonCreator + public NavXRumbleComponent(@NotNull @JsonProperty(required = true) MappedAHRS navX, + @NotNull @JsonProperty(required = true) List rumbleables, + @JsonProperty(required = true) double minJerk, + @JsonProperty(required = true) double maxJerk, + boolean yIsFrontBack, + boolean invertLeftRight) { + this.navX = navX; + this.rumbleables = rumbleables; + //Convert from feet/(sec^3) to Gs/millis. + this.minJerk = minJerk * FPS_CUBED_TO_GS_PER_MILLIS; + this.maxJerk = maxJerk * FPS_CUBED_TO_GS_PER_MILLIS; + this.yIsFrontBack = yIsFrontBack; + this.invertLeftRight = invertLeftRight; + timeLastCalled = 0; + lastFrontBackAccel = 0; + lastLeftRightAccel = 0; + } + + /** + * Read the NavX jerk data and rumble the joysticks based off of it. + */ + @Override + public void run() { + if (yIsFrontBack) { + //Put an abs() here because we can't differentiate front vs back when rumbling, so we only care about magnitude. + frontBack = Math.abs(navX.getWorldLinearAccelY()); + leftRight = navX.getWorldLinearAccelX() * (invertLeftRight ? -1 : 1); + } else { + frontBack = Math.abs(navX.getWorldLinearAccelX()); + leftRight = navX.getWorldLinearAccelY() * (invertLeftRight ? -1 : 1); + } + + //Left is negative jerk, so we subtract it from left so that when we're going left, left is bigger and vice versa + left = ((frontBack - lastFrontBackAccel) - (leftRight - lastLeftRightAccel)) / (Clock.currentTimeMillis() - timeLastCalled); + right = ((frontBack - lastFrontBackAccel) + (leftRight - lastLeftRightAccel)) / (Clock.currentTimeMillis() - timeLastCalled); + + if (left > minJerk) { + left = (left - minJerk) / maxJerk; + } else { + left = 0; + } + + if (right > minJerk) { + right = (right - minJerk) / maxJerk; + } else { + right = 0; + } + + for (Rumbleable rumbleable : rumbleables) { + rumbleable.rumble(left, right); + } + + lastLeftRightAccel = leftRight; + lastFrontBackAccel = frontBack; + timeLastCalled = Clock.currentTimeMillis(); + } + +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/ShiftWithSensorComponent.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/ShiftWithSensorComponent.java index 9edaab25..9472765a 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/ShiftWithSensorComponent.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/components/ShiftWithSensorComponent.java @@ -37,38 +37,50 @@ public class ShiftWithSensorComponent extends ShiftComponent { */ @NotNull private final List motorsToDisable; + /** - * The timer for how long the piston can be considered shifting before we ignore the sensors and re-enable the motors. + * The timer for how long the piston can be considered shifting before we ignore the sensors and re-enable the + * motors. */ @NotNull private final BufferTimer motorDisableTimer; + /** * The Notifier that runs checkToReenable periodically. */ @NotNull private final Notifier sensorChecker; + /** * The period for the loop that checks the sensors and enables/disables the motors, in seconds. */ private final double sensorCheckerPeriodSecs; + /** * Whether the piston's position was correct the last time checkToReenable was run. */ private boolean pistonWasCorrect; + /** + * Whether the piston's position is currently correct. Field to avoid garbage collection. + */ + private boolean pistonCorrect; + /** * Default constructor. * * @param otherShiftables All objects that should be shifted when this component's piston is. * @param piston The piston that shifts. * @param lowGearPistonPos The piston position for low gear. Defaults to Forward. - * @param startingGear The gear to start in. Can be null, and if it is, the starting gear is gotten from the - * piston's position. + * @param startingGear The gear to start in. Can be null, and if it is, the starting gear is gotten from + * the piston's position. * @param highGearSensors The reed switches that detect if the shifter pistons are in high gear. * @param lowGearSensors The reed switches that detect if the shifter pistons are in low gear. * @param motorsToDisable The motors that should be disabled while the piston is shifting. - * @param motorDisableTimer The timer for how long the piston can be considered shifting before we ignore the sensors and re-enable the motors. - * @param sensorCheckerPeriodSecs The period for the loop that checks the sensors and enables/disables the motors, in seconds. + * @param motorDisableTimer The timer for how long the piston can be considered shifting before we ignore the + * sensors and re-enable the motors. + * @param sensorCheckerPeriodSecs The period for the loop that checks the sensors and enables/disables the motors, + * in seconds. */ @JsonCreator public ShiftWithSensorComponent(@NotNull @JsonProperty(required = true) List otherShiftables, @@ -95,7 +107,7 @@ public ShiftWithSensorComponent(@NotNull @JsonProperty(required = true) List extends YamlCommandWrapper { +public class DetermineNominalVoltage extends YamlCommandWrapper { /** * The drive subsystem to execute this command on. @@ -76,7 +76,7 @@ protected void execute() { */ @Override protected boolean isFinished() { - return Math.max(Math.abs(subsystem.getLeftVel()), Math.abs(subsystem.getRightVel())) >= minSpeed; + return Math.max(Math.abs(subsystem.getLeftVelCached()), Math.abs(subsystem.getRightVelCached())) >= minSpeed; } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineVelVsVoltage.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineVelVsVoltage.java new file mode 100644 index 00000000..d9de20db --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineVelVsVoltage.java @@ -0,0 +1,197 @@ +package org.usfirst.frc.team449.robot.drive.unidirectional.commands; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandWrapper; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlSubsystem; +import org.usfirst.frc.team449.robot.other.Clock; +import org.usfirst.frc.team449.robot.other.Logger; + +/** + * A command to run the robot at a range of voltages and record the velocity. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class DetermineVelVsVoltage extends YamlCommandWrapper { + + /** + * The subsystem to execute this command on. + */ + @NotNull + private final T subsystem; + + /** + * How far, in feet, to drive for each trial. + */ + private final double distanceToDrive; + + /** + * How many trials to do for each voltage. + */ + private final int numTrials; + + /** + * A list of all the voltages to be tested, from (0, 1]. + */ + private final double[] voltagePercentsToTest; + + /** + * The maximum measured speed, in feet/sec, for the current trial. + */ + private double maxSpeedForTrial; + + /** + * The time the maximum speed for this trial was measured at. + */ + private long timeMaxMeasuredAt; + + /** + * The index, in the list of voltages to test, of the voltage currently being tested. + */ + private int voltageIndex; + + /** + * How many trials are left for the current voltage. + */ + private int trialsRemaining; + + /** + * The current sign of the output. Alternates every trial so we just drive back and forth. + */ + private int sign; + + /** + * The average speed of the two sides. Field to avoid garbage collection. + */ + private double avgSpeed; + + /** + * Whether the distance for this trial has been driven. Field to avoid garbage collection. + */ + private boolean drivenDistance; + + /** + * Default constructor. + * + * @param subsystem The subsystem to execute this command on. + * @param distanceToDrive How far, in feet, to drive for each trial. + * @param numTrials How many trials to do for each voltage. + * @param voltagesToTest A list of all the voltages to be tested, from (0, 12]. + */ + @JsonCreator + public DetermineVelVsVoltage(@NotNull @JsonProperty(required = true) T subsystem, + @JsonProperty(required = true) double distanceToDrive, + @JsonProperty(required = true) int numTrials, + @JsonProperty(required = true) double[] voltagesToTest) { + this.subsystem = subsystem; + this.distanceToDrive = distanceToDrive; + this.numTrials = numTrials; + + //Convert from volts to percentages because CANTalons. + this.voltagePercentsToTest = new double[voltagesToTest.length]; + for (int i = 0; i < voltagesToTest.length; i++) { + this.voltagePercentsToTest[i] = voltagesToTest[i] / 12.; + } + } + + /** + * Reset the encoder position and variables. + */ + @Override + protected void initialize() { + subsystem.resetPosition(); + sign = 1; + voltageIndex = 0; + maxSpeedForTrial = 0; + timeMaxMeasuredAt = 0; + trialsRemaining = numTrials; + subsystem.setOutput(voltagePercentsToTest[voltageIndex], voltagePercentsToTest[voltageIndex]); + SmartDashboard.putNumber("Desired voltage", voltagePercentsToTest[voltageIndex] * 12); + } + + /** + * Update the max speed for this trial and check if this trial is finished. + */ + @Override + protected void execute() { + //Multiply each by sign so that only the movement in the correct direction is counted and leftover momentum from + // the previous trial isn't. + + avgSpeed = (sign * subsystem.getLeftVelCached() + sign * subsystem.getRightVelCached()) / 2.; + + if (avgSpeed > maxSpeedForTrial) { + maxSpeedForTrial = avgSpeed; + timeMaxMeasuredAt = Clock.currentTimeMillis(); + } + + SmartDashboard.putNumber("Average Distance", (subsystem.getLeftPosCached() + subsystem.getRightPosCached()) / 2.); + SmartDashboard.putNumber("Average Speed", avgSpeed); + + //Check if we've driven past the given distance + if (sign == -1) { + drivenDistance = (subsystem.getLeftPosCached() + subsystem.getRightPosCached()) / 2. <= 0; + } else { + drivenDistance = (subsystem.getLeftPosCached() + subsystem.getRightPosCached()) / 2. >= distanceToDrive; + } + + //If we've driven past, log the max speed and reset the variables. + if (drivenDistance) { + //Log + Logger.addEvent(Long.toString(timeMaxMeasuredAt), this.getClass()); + + //Reset + maxSpeedForTrial = 0; + + //Switch direction + sign *= -1; + + //Finished a trial + trialsRemaining--; + + //Go onto the next voltage if we've done enough trials + if (trialsRemaining <= 0) { + trialsRemaining = numTrials; + voltageIndex++; + + //Exit if we've done all trials for all voltages + if (voltageIndex >= voltagePercentsToTest.length) { + return; + } + } + + //Set the output to the correct voltage and sign + subsystem.setOutput(sign * voltagePercentsToTest[voltageIndex], sign * voltagePercentsToTest[voltageIndex]); + SmartDashboard.putNumber("Desired voltage", voltagePercentsToTest[voltageIndex] * 12.); + } + } + + /** + * Finish when all trials have been run. + * + * @return true if all trials have be run, false otherwise. + */ + @Override + protected boolean isFinished() { + return voltageIndex >= voltagePercentsToTest.length; + } + + /** + * Do nothing, no logging because we want to be able to use R's subset method to find the max speeds. + */ + @Override + protected void end() { + //Nothing! + } + + /** + * Log when interrupted. + */ + @Override + protected void interrupted() { + Logger.addEvent("DetermineVelVsVoltage Interrupted!", this.getClass()); + } +} \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveAtSpeed.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveAtSpeed.java index f546a021..88b9e99f 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveAtSpeed.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveAtSpeed.java @@ -15,7 +15,7 @@ * Go at a certain velocity for a set number of seconds */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class DriveAtSpeed extends YamlCommandWrapper { +public class DriveAtSpeed extends YamlCommandWrapper { /** * Speed to go at diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveStraight.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveStraight.java index 11e5ad98..9327bfb6 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveStraight.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DriveStraight.java @@ -15,7 +15,7 @@ * Drives straight when using a tank drive. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class DriveStraight extends YamlCommandWrapper { +public class DriveStraight extends YamlCommandWrapper { /** * The oi that this command gets input from. @@ -34,11 +34,6 @@ public class DriveStraight extend @NotNull private final T subsystem; - /** - * The throttle gotten from the joystick. This is a field instead of a local variable to avoid garbage collection. - */ - private double throttle; - /** * Drive straight without NavX stabilization. * @@ -71,12 +66,10 @@ protected void initialize() { @Override protected void execute() { if (useLeft) { - throttle = oi.getLeftThrottle(); + subsystem.setOutput(oi.getLeftOutputCached(), oi.getLeftOutputCached()); } else { - throttle = oi.getRightThrottle(); + subsystem.setOutput(oi.getRightOutputCached(), oi.getRightOutputCached());; } - - subsystem.setOutput(throttle, throttle); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDBackAndForth.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDBackAndForth.java index ad3ca480..b2931f8c 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDBackAndForth.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDBackAndForth.java @@ -13,7 +13,7 @@ * Drive back and forth to tune PID. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class PIDBackAndForth extends YamlCommandGroupWrapper { +public class PIDBackAndForth extends YamlCommandGroupWrapper { /** * Instantiate the CommandGroup diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDTest.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDTest.java index 8cb5f5e3..7f5fefe6 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDTest.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/PIDTest.java @@ -13,7 +13,7 @@ * Drive forward at constant speed then stop to tune PID. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class PIDTest extends YamlCommandGroupWrapper { +public class PIDTest extends YamlCommandGroupWrapper { /** * Default constructor diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/SimpleUnidirectionalDrive.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/SimpleUnidirectionalDrive.java index 70afb9c5..f058aa22 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/SimpleUnidirectionalDrive.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/SimpleUnidirectionalDrive.java @@ -15,7 +15,7 @@ * Very simple unidirectional drive control. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class SimpleUnidirectionalDrive extends YamlCommandWrapper { +public class SimpleUnidirectionalDrive extends YamlCommandWrapper { /** * The OI used for input. @@ -57,7 +57,7 @@ protected void initialize() { */ @Override protected void execute() { - subsystem.setOutput(oi.getLeftOutput(), oi.getRightOutput()); + subsystem.setOutput(oi.getLeftOutputCached(), oi.getRightOutputCached()); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/VoltageRamp.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/VoltageRamp.java new file mode 100644 index 00000000..dca51292 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/drive/unidirectional/commands/VoltageRamp.java @@ -0,0 +1,99 @@ +package org.usfirst.frc.team449.robot.drive.unidirectional.commands; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional; +import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandWrapper; +import org.usfirst.frc.team449.robot.other.Clock; +import org.usfirst.frc.team449.robot.other.Logger; + +/** + * A command to ramp up the motors to full power at a given voltage rate. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class VoltageRamp extends YamlCommandWrapper { + + /** + * The subsystem to execute this command on. + */ + @NotNull + private final DriveUnidirectional subsystem; + + /** + * The number of percentage points to increase motor output by per millisecond. + */ + private final double percentPerMillis; + + /** + * The last time execute() was run. + */ + private long lastTime; + + /** + * The output to give to the motors. + */ + private double output; + + /** + * Default constructor + * + * @param subsystem The subsystem to execute this command on + * @param voltsPerSecond How many volts to increase the output by per second. + */ + @JsonCreator + public VoltageRamp(@NotNull @JsonProperty(required = true) DriveUnidirectional subsystem, + @JsonProperty(required = true) double voltsPerSecond) { + this.subsystem = subsystem; + this.percentPerMillis = voltsPerSecond / 12. / 1000.; + } + + /** + * Reset the output + */ + @Override + protected void initialize() { + Logger.addEvent("VoltageRamp init.", this.getClass()); + lastTime = Clock.currentTimeMillis(); + output = 0; + } + + /** + * Update the output based on how long it's been since execute() was last run. + */ + @Override + protected void execute() { + output += percentPerMillis * (Clock.currentTimeMillis() - lastTime); + subsystem.setOutput(output, output); + lastTime = Clock.currentTimeMillis(); + } + + /** + * Exit if the output is greater than the motors can produce. + * + * @return true if the output is greater than or equal to 1, false otherwise. + */ + @Override + protected boolean isFinished() { + return output >= 1.; + } + + /** + * Log and stop on end. + */ + @Override + protected void end() { + subsystem.setOutput(0, 0); + Logger.addEvent("VoltageRamp end.", this.getClass()); + } + + /** + * Log on interrupt. + */ + @Override + protected void interrupted() { + Logger.addEvent("VoltageRamp Interrupted!", this.getClass()); + } +} \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/rumbleable/Rumbleable.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/rumbleable/Rumbleable.java new file mode 100644 index 00000000..76ad8060 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/rumbleable/Rumbleable.java @@ -0,0 +1,19 @@ +package org.usfirst.frc.team449.robot.generalInterfaces.rumbleable; + +import com.fasterxml.jackson.annotation.JsonTypeInfo; + +/** + * An interface for any sort of OI device that can rumble to give feedback to the driver. + */ +@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") +public interface Rumbleable { + + /** + * Rumble at a given strength on each side of the device. + * + * @param left The strength to rumble the left side, on [-1, 1] + * @param right The strength to rumble the right side, on [-1, 1] + */ + void rumble(double left, double right); + +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/updatable/Updatable.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/updatable/Updatable.java new file mode 100644 index 00000000..60047045 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/generalInterfaces/updatable/Updatable.java @@ -0,0 +1,15 @@ +package org.usfirst.frc.team449.robot.generalInterfaces.updatable; + +import com.fasterxml.jackson.annotation.JsonTypeInfo; + +/** + * An interface for any object that caches values. + */ +@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") +public interface Updatable { + + /** + * Updates all cached values with current ones. + */ + void update(); +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/FPSTalon.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/FPSTalon.java index b26254db..66492f68 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/FPSTalon.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/FPSTalon.java @@ -15,6 +15,7 @@ import org.usfirst.frc.team449.robot.other.Logger; import org.usfirst.frc.team449.robot.other.MotionProfileData; +import java.util.Arrays; import java.util.HashMap; import java.util.List; import java.util.Map; @@ -66,12 +67,6 @@ public class FPSTalon implements SimpleMotor, Shiftable { @NotNull private final CANTalon.MotionProfileStatus motionProfileStatus; - /** - * The time at which the motion profile status was last checked. Only getting the status once per tic avoids CAN - * traffic. - */ - private long timeMPStatusLastRead; - /** * A notifier that moves points from the API-level buffer to the talon-level one. */ @@ -88,16 +83,33 @@ public class FPSTalon implements SimpleMotor, Shiftable { @NotNull private final Map perGearSettings; + /** + * Whether or not to invert the motor in voltage mode. + */ + private final boolean invertInVoltage; + /** * The settings currently being used by this Talon. */ @NotNull protected PerGearSettings currentGearSettings; + /** + * The time at which the motion profile status was last checked. Only getting the status once per tic avoids CAN + * traffic. + */ + private long timeMPStatusLastRead; + + /** + * RPS as used in a unit conversion method. Field to avoid garbage collection. + */ + private Double RPS; + /** * Default constructor. * * @param port CAN port of this Talon. + * @param invertInVoltage Whether or not to invert the motor in voltage mode. * @param reverseOutput Whether to reverse the output (identical effect to inverting outside of * position PID) * @param enableBrakeMode Whether to brake or coast when stopped. @@ -105,14 +117,15 @@ public class FPSTalon implements SimpleMotor, Shiftable { * the forward limit switch is disabled. * @param revLimitSwitchNormallyOpen Whether the reverse limit switch is normally open or closed. If this is null, * the reverse limit switch is disabled. - * @param fwdSoftLimit The forward software limit, in feet. If this is null, the forward software limit is - * disabled. - * @param revSoftLimit The reverse software limit, in feet. If this is null, the reverse software limit is - * disabled. + * @param fwdSoftLimit The forward software limit, in feet. If this is null, the forward software + * limit is disabled. + * @param revSoftLimit The reverse software limit, in feet. If this is null, the reverse software + * limit is disabled. * @param postEncoderGearing The coefficient the output changes by after being measured by the encoder, e.g. * this would be 1/70 if there was a 70:1 gearing between the encoder and the * final output. Defaults to 1. - * @param feetPerRotation The number of feet travelled per rotation of the motor this is attached to. Defaults to 1. + * @param feetPerRotation The number of feet travelled per rotation of the motor this is attached to. + * Defaults to 1. * @param currentLimit The max amps this device can draw. If this is null, no current limit is used. * @param maxClosedLoopVoltage The voltage to scale closed-loop output based on, e.g. closed-loop output of 1 * will produce this voltage, output of 0.5 will produce half, etc. This feature @@ -121,7 +134,8 @@ public class FPSTalon implements SimpleMotor, Shiftable { * null if there is no encoder attached to this Talon. * @param encoderCPR The counts per rotation of the encoder on this Talon. Can be null if * feedbackDevice is, but otherwise must have a value. - * @param reverseSensor Whether or not to reverse the reading from the encoder on this Talon. Ignored if feedbackDevice is null. Defaults to false. + * @param reverseSensor Whether or not to reverse the reading from the encoder on this Talon. Ignored + * if feedbackDevice is null. Defaults to false. * @param perGearSettings The settings for each gear this motor has. Can be null to use default values * and gear # of zero. Gear numbers can't be repeated. * @param startingGear The gear to start in. Can be null to use startingGearNum instead. @@ -131,10 +145,13 @@ public class FPSTalon implements SimpleMotor, Shiftable { * starting a profile. Defaults to 20. * @param updaterProcessPeriodSecs The period for the Notifier that moves points between the MP buffers, in * seconds. Defaults to 0.005. + * @param statusFrameRatesMillis The update rates, in millis, for each of the Talon status frames. + * @param controlFrameRateMillis The update rate, in milliseconds, for the control frame. Defaults to 10. * @param slaves The other {@link CANTalon}s that are slaved to this one. */ @JsonCreator public FPSTalon(@JsonProperty(required = true) int port, + boolean invertInVoltage, boolean reverseOutput, @JsonProperty(required = true) boolean enableBrakeMode, @Nullable Boolean fwdLimitSwitchNormallyOpen, @@ -153,9 +170,11 @@ public FPSTalon(@JsonProperty(required = true) int port, @Nullable Integer startingGearNum, @Nullable Integer minNumPointsInBottomBuffer, @Nullable Double updaterProcessPeriodSecs, + @Nullable Map statusFrameRatesMillis, + @Nullable Integer controlFrameRateMillis, @Nullable List slaves) { //Instantiate the base CANTalon this is a wrapper on. - canTalon = new CANTalon(port); + canTalon = new CANTalon(port, controlFrameRateMillis != null ? controlFrameRateMillis : 10); //Set this to false because we only use reverseOutput for slaves. canTalon.reverseOutput(reverseOutput); //NO TOUCHY @@ -163,7 +182,15 @@ public FPSTalon(@JsonProperty(required = true) int port, //Set brake mode canTalon.enableBrakeMode(enableBrakeMode); + //Set frame rates + if (statusFrameRatesMillis != null) { + for (CANTalon.StatusFrameRate statusFrameRate : statusFrameRatesMillis.keySet()) { + canTalon.setStatusFrameRateMs(statusFrameRate, statusFrameRatesMillis.get(statusFrameRate)); + } + } + //Set fields + this.invertInVoltage = invertInVoltage; this.feetPerRotation = feetPerRotation != null ? feetPerRotation : 1; this.updaterProcessPeriodSecs = updaterProcessPeriodSecs != null ? updaterProcessPeriodSecs : 0.005; this.minNumPointsInBottomBuffer = minNumPointsInBottomBuffer != null ? minNumPointsInBottomBuffer : 20; @@ -219,8 +246,8 @@ public FPSTalon(@JsonProperty(required = true) int port, //CTRE encoder use RPM instead of native units, and can be used as QuadEncoders, so we switch them to avoid //having to support RPM. if (feedbackDevice.equals(CANTalon.FeedbackDevice.CtreMagEncoder_Absolute) || - feedbackDevice.equals(CANTalon.FeedbackDevice.CtreMagEncoder_Relative)){ - this.feedbackDevice= CANTalon.FeedbackDevice.QuadEncoder; + feedbackDevice.equals(CANTalon.FeedbackDevice.CtreMagEncoder_Relative)) { + this.feedbackDevice = CANTalon.FeedbackDevice.QuadEncoder; } else { this.feedbackDevice = feedbackDevice; } @@ -316,7 +343,7 @@ public void setPercentVoltage(double percentVoltage) { canTalon.changeControlMode(CANTalon.TalonControlMode.PercentVbus); //Set the setpoint to the input given. - canTalon.set(percentVoltage); + canTalon.set(percentVoltage * (invertInVoltage ? -1 : 1)); } /** @@ -334,16 +361,24 @@ public int getGear() { */ @Override public void setGear(int gear) { + //Set the current gear currentGearSettings = perGearSettings.get(gear); + + //Set general max voltage + canTalon.configMaxOutputVoltage(Math.max(currentGearSettings.getFwdPeakOutputVoltage(), -currentGearSettings.getRevPeakOutputVoltage())); + + //Set closed loop max and min voltages canTalon.configPeakOutputVoltage(currentGearSettings.getFwdPeakOutputVoltage(), currentGearSettings.getRevPeakOutputVoltage()); canTalon.configNominalOutputVoltage(currentGearSettings.getFwdNominalOutputVoltage(), currentGearSettings.getRevNominalOutputVoltage()); + + //Set PID stuff if (currentGearSettings.getMaxSpeed() != null) { //Put driving constants in slot 0 canTalon.setPID(currentGearSettings.getkP(), currentGearSettings.getkI(), currentGearSettings.getkD(), 1023. / FPSToEncoder(currentGearSettings.getMaxSpeed()), 0, currentGearSettings.getClosedLoopRampRate(), 0); //Put MP constants in slot 1 - canTalon.setPID(currentGearSettings.getMotionProfileP(), currentGearSettings.getMotionProfileI(), currentGearSettings.getMotionProfileD(), - 1023. / FPSToEncoder(currentGearSettings.getMaxSpeed()), 0, currentGearSettings.getClosedLoopRampRate(), 1); + canTalon.setPID(currentGearSettings.getMotionProfilePFwd(), currentGearSettings.getMotionProfileIFwd(), currentGearSettings.getMotionProfileDFwd(), + 1023. / FPSToEncoder(currentGearSettings.getMaxSpeedMPFwd()), 0, currentGearSettings.getClosedLoopRampRate(), 1); canTalon.setProfile(0); } } @@ -359,8 +394,7 @@ protected Double encoderToFeet(double nativeUnits) { if (encoderCPR == null) { return null; } - double rotations = nativeUnits / (encoderCPR * 4) * postEncoderGearing; - return rotations * feetPerRotation; + return nativeUnits / (encoderCPR * 4) * postEncoderGearing * feetPerRotation; } /** @@ -375,8 +409,7 @@ protected Double feetToEncoder(double feet) { if (encoderCPR == null) { return null; } - double rotations = feet / feetPerRotation; - return rotations * (encoderCPR * 4) / postEncoderGearing; + return feet / feetPerRotation * (encoderCPR * 4) / postEncoderGearing; } /** @@ -389,7 +422,7 @@ protected Double feetToEncoder(double feet) { */ @Nullable protected Double encoderToFPS(double encoderReading) { - Double RPS = nativeToRPS(encoderReading); + RPS = nativeToRPS(encoderReading); if (RPS == null) { return null; } @@ -397,8 +430,8 @@ protected Double encoderToFPS(double encoderReading) { } /** - * Converts from the velocity of the output shaft to what the talon's getVelocity() method would read at that velocity. - * Note this DOES account for post-encoder gearing. + * Converts from the velocity of the output shaft to what the talon's getVelocity() method would read at that + * velocity. Note this DOES account for post-encoder gearing. * * @param FPS The velocity of the output shaft, in FPS. * @return What the raw encoder reading would be at that velocity, or null if no encoder CPR was given. @@ -450,6 +483,20 @@ public Double getVelocity() { return encoderToFPS(canTalon.getSpeed()); } + /** + * Set the velocity for the motor to go at. + * + * @param velocity the desired velocity, on [-1, 1]. + */ + @Override + public void setVelocity(double velocity) { + if (currentGearSettings.getMaxSpeed() != null) { + setVelocityFPS(velocity * currentGearSettings.getMaxSpeed()); + } else { + setPercentVoltage(velocity); + } + } + /** * Give a velocity closed loop setpoint in FPS. * @@ -499,20 +546,6 @@ public double getOutputCurrent() { return canTalon.getOutputCurrent(); } - /** - * Set the velocity for the motor to go at. - * - * @param velocity the desired velocity, on [-1, 1]. - */ - @Override - public void setVelocity(double velocity) { - if (currentGearSettings.getMaxSpeed() != null) { - setVelocityFPS(velocity * currentGearSettings.getMaxSpeed()); - } else { - setPercentVoltage(velocity); - } - } - /** * Enables the motor, if applicable. */ @@ -637,6 +670,23 @@ public void loadProfile(MotionProfileData data) { //Read velocityOnly out here so we only have to call data.isVelocityOnly() once. boolean velocityOnly = data.isVelocityOnly(); + //Declare this out here to avoid garbage collection + double velPlusAccel; + + //Set proper PID constants + if (data.isInverted()) { + canTalon.setPID(currentGearSettings.getMotionProfilePRev(), currentGearSettings.getMotionProfileIRev(), + currentGearSettings.getMotionProfileDRev(), + 1023. / FPSToEncoder(currentGearSettings.getMaxSpeedMPRev()), 0, + currentGearSettings.getClosedLoopRampRate(), 1); + } else { + canTalon.setPID(currentGearSettings.getMotionProfilePFwd(), currentGearSettings.getMotionProfileIFwd(), + currentGearSettings.getMotionProfileDFwd(), + 1023. / FPSToEncoder(currentGearSettings.getMaxSpeedMPFwd()), 0, + currentGearSettings.getClosedLoopRampRate(), 1); + } + + //Load in profiles for (int i = 0; i < data.getData().length; ++i) { CANTalon.TrajectoryPoint point = new CANTalon.TrajectoryPoint(); //Set parameters that are true for all points @@ -644,9 +694,25 @@ public void loadProfile(MotionProfileData data) { point.velocityOnly = velocityOnly; // true => no position servo just velocity feedforward // Set all the fields of the profile point - point.position = feetToEncoder(data.getData()[i][0]); - point.velocity = FPSToEncoder(data.getData()[i][1]); - point.timeDurMs = (int) (data.getData()[i][2] * 1000.); + point.position = feetToEncoder(data.getData()[i][0]) * (data.isInverted() ? -1 : 1); + + //Calculate vel based off inversion + if (data.isInverted()) { + velPlusAccel = -data.getData()[i][1] - currentGearSettings.getFrictionCompFPSRev() + + -data.getData()[i][2] * currentGearSettings.getKaOverKvRev(); + } else { + velPlusAccel = data.getData()[i][1] + data.getData()[i][2] * currentGearSettings.getKaOverKvFwd() + + currentGearSettings.getFrictionCompFPSFwd(); + } + Logger.addEvent("VelPlusAccel: " + velPlusAccel, this.getClass()); + point.velocity = FPSToEncoder(velPlusAccel); + + //Doing vel+accel shouldn't lead to impossible setpoints, so if it does, we log so we know to change either the profile or kA. + if (Math.abs(velPlusAccel) > currentGearSettings.getMaxSpeed()) { + System.out.println("Point " + Arrays.toString(data.getData()[i]) + " has an unattainable velocity+acceleration setpoint!"); + Logger.addEvent("Point " + Arrays.toString(data.getData()[i]) + " has an unattainable velocity+acceleration setpoint!", this.getClass()); + } + point.timeDurMs = (int) data.getData()[i][3]; point.zeroPos = i == 0; // If it's the first point, set the encoder position to 0. point.isLastPoint = (i + 1) == data.getData().length; // If it's the last point, isLastPoint = true @@ -749,9 +815,31 @@ protected static class PerGearSettings { private final double kP, kI, kD; /** - * The PID constants for motion profiles in this gear. Ignored if maxSpeed is null. + * The forwards PID constants for motion profiles in this gear. Ignored if maxSpeed is null. + */ + private final double motionProfilePFwd, motionProfileIFwd, motionProfileDFwd; + + /** + * The reverse PID constants for motion profiles in this gear. Ignored if maxSpeed is null. + */ + private final double motionProfilePRev, motionProfileIRev, motionProfileDRev; + + /** + * The ratio of acceleration to velocity used to convert acceleration setpoints to delta velocity in each + * direction. + */ + private final double kaOverKvFwd, kaOverKvRev; + + /** + * The "fake" maximum speed to use for MP mode in each direction, maxVoltage*(slope of vel vs. voltage curve). + */ + @Nullable + private final Double maxSpeedMPFwd, maxSpeedMPRev; + + /** + * The speed, in FPS, to add to all MP velocity setpoints to account for friction in each direction. */ - private final double motionProfileP, motionProfileI, motionProfileD; + private final double frictionCompFPSFwd, frictionCompFPSRev; /** * Default constructor. @@ -778,12 +866,32 @@ protected static class PerGearSettings { * null. Defaults to 0. * @param kD The derivative PID constant for the motor in this gear. Ignored if maxSpeed is * null. Defaults to 0. - * @param motionProfileP The proportional PID constant for motion profiles in this gear. Ignored if - * maxSpeed is null. Defaults to 0. - * @param motionProfileI The integral PID constant for motion profiles in this gear. Ignored if - * maxSpeed is null. Defaults to 0. - * @param motionProfileD The derivative PID constant for motion profiles in this gear. Ignored if - * maxSpeed is null. Defaults to 0. + * @param motionProfilePFwd The proportional PID constant for forwards motion profiles in this gear. + * Ignored if maxSpeed is null. Defaults to 0. + * @param motionProfileIFwd The integral PID constant for forwards motion profiles in this gear. Ignored + * if maxSpeed is null. Defaults to 0. + * @param motionProfileDFwd The derivative PID constant for forwards motion profiles in this gear. Ignored + * if maxSpeed is null. Defaults to 0. + * @param motionProfilePRev The proportional PID constant for reverse motion profiles in this gear. + * Ignored if maxSpeed is null. Defaults to motionProfilePFwd. + * @param motionProfileIRev The integral PID constant for reverse motion profiles in this gear. Ignored if + * maxSpeed is null. Defaults to motionProfileIFwd. + * @param motionProfileDRev The derivative PID constant for reverse motion profiles in this gear. Ignored + * if maxSpeed is null. Defaults to motionProfileDFwd. + * @param maxAccelFwd The maximum forwards acceleration the robot is capable of in this gear, + * theoretically stall torque of the drive output * wheel radius / (robot + * mass/2). Can be null to not use acceleration feed-forward. + * @param maxAccelRev The maximum reverse acceleration the robot is capable of in this gear, + * theoretically stall torque of the drive output * wheel radius / (robot + * mass/2). Defaults to maxAccelFwd. + * @param maxSpeedMPFwd The "fake" maximum speed to use for the forwards direction of MP mode, + * maxVoltage*(slope of vel vs. voltage curve). Defaults to regular max speed. + * @param maxSpeedMPRev The "fake" maximum speed to use for the reverse direction of MP mode, + * maxVoltage*(slope of vel vs. voltage curve). Defaults to maxSpeedMPFwd. + * @param frictionCompFPSFwd The speed, in FPS, to add to all MP velocity setpoints in the forwards + * direction to account for friction. Defaults to 0. + * @param frictionCompFPSRev The speed, in FPS, to add to all MP velocity setpoints in the reverse + * direction to account for friction. Defaults to frictionCompFPSFwd. */ @JsonCreator public PerGearSettings(int gearNum, @@ -797,9 +905,18 @@ public PerGearSettings(int gearNum, double kP, double kI, double kD, - double motionProfileP, - double motionProfileI, - double motionProfileD) { + double motionProfilePFwd, + double motionProfileIFwd, + double motionProfileDFwd, + Double motionProfilePRev, + Double motionProfileIRev, + Double motionProfileDRev, + @Nullable Double maxAccelFwd, + @Nullable Double maxAccelRev, + @Nullable Double maxSpeedMPFwd, + double frictionCompFPSFwd, + @Nullable Double maxSpeedMPRev, + @Nullable Double frictionCompFPSRev) { this.gear = gear != null ? gear.getNumVal() : gearNum; this.fwdPeakOutputVoltage = fwdPeakOutputVoltage != null ? fwdPeakOutputVoltage : 12; this.revPeakOutputVoltage = revPeakOutputVoltage != null ? revPeakOutputVoltage : -this.fwdPeakOutputVoltage; @@ -816,16 +933,31 @@ public PerGearSettings(int gearNum, this.kP = kP; this.kI = kI; this.kD = kD; - this.motionProfileP = motionProfileP; - this.motionProfileI = motionProfileI; - this.motionProfileD = motionProfileD; + this.motionProfilePFwd = motionProfilePFwd; + this.motionProfileIFwd = motionProfileIFwd; + this.motionProfileDFwd = motionProfileDFwd; + this.motionProfilePRev = motionProfilePRev != null ? motionProfilePRev : this.motionProfilePFwd; + this.motionProfileIRev = motionProfileIRev != null ? motionProfileIRev : this.motionProfileIFwd; + this.motionProfileDRev = motionProfileDRev != null ? motionProfileDRev : this.motionProfileDFwd; + this.maxSpeedMPFwd = maxSpeedMPFwd != null ? maxSpeedMPFwd : maxSpeed; + this.maxSpeedMPRev = maxSpeedMPRev != null ? maxSpeedMPRev : this.maxSpeedMPFwd; + + if (this.maxSpeedMPFwd != null && maxAccelFwd != null) { + this.kaOverKvFwd = this.maxSpeedMPFwd / maxAccelFwd; + this.kaOverKvRev = maxAccelRev != null ? this.maxSpeedMPRev / maxAccelRev : this.kaOverKvFwd; + } else { + this.kaOverKvFwd = 0; + this.kaOverKvRev = 0; + } + this.frictionCompFPSFwd = frictionCompFPSFwd; + this.frictionCompFPSRev = frictionCompFPSRev != null ? frictionCompFPSRev : frictionCompFPSFwd; } /** * Empty constructor that uses all default options. */ public PerGearSettings() { - this(0, null, null, null, null, null, null, null, 0, 0, 0, 0, 0, 0); + this(0, null, null, null, null, null, null, null, 0, 0, 0, 0, 0, 0, null, null, null, null, null, null, 0, null, null); } /** @@ -904,22 +1036,60 @@ public double getkD() { /** * @return The proportional PID constant for motion profiles in this gear. */ - public double getMotionProfileP() { - return motionProfileP; + public double getMotionProfilePFwd() { + return motionProfilePFwd; } /** * @return The integral PID constant for motion profiles in this gear. */ - public double getMotionProfileI() { - return motionProfileI; + public double getMotionProfileIFwd() { + return motionProfileIFwd; } /** * @return The derivative PID constant for motion profiles in this gear. */ - public double getMotionProfileD() { - return motionProfileD; + public double getMotionProfileDFwd() { + return motionProfileDFwd; + } + + public double getKaOverKvFwd() { + return kaOverKvFwd; + } + + @Nullable + public Double getMaxSpeedMPFwd() { + return maxSpeedMPFwd; + } + + @Nullable + public Double getMaxSpeedMPRev() { + return maxSpeedMPRev; + } + + public double getFrictionCompFPSFwd() { + return frictionCompFPSFwd; + } + + public double getFrictionCompFPSRev() { + return frictionCompFPSRev; + } + + public double getMotionProfilePRev() { + return motionProfilePRev; + } + + public double getMotionProfileIRev() { + return motionProfileIRev; + } + + public double getMotionProfileDRev() { + return motionProfileDRev; + } + + public double getKaOverKvRev() { + return kaOverKvRev; } } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedAHRS.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedAHRS.java index 9b0b54ac..5d142798 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedAHRS.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedAHRS.java @@ -6,6 +6,7 @@ import com.fasterxml.jackson.annotation.ObjectIdGenerators; import com.kauailabs.navx.frc.AHRS; import edu.wpi.first.wpilibj.SPI; +import org.jetbrains.annotations.Contract; /** * A Jackson-compatible wrapper for the NavX. @@ -23,4 +24,15 @@ public MappedAHRS(@JsonProperty(required = true) SPI.Port port) { super(port); this.reset(); } + + /** + * Convert from gs (acceleration due to gravity) to feet/(second^2). + * + * @param accelGs An acceleration in gs. + * @return That acceleration in feet/(sec^2) + */ + @Contract(pure = true) + public static double gsToFeetPerSecondSquared(double accelGs) { + return accelGs * 32.17; //Wolfram alpha said so + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedButton.java new file mode 100644 index 00000000..48548b05 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedButton.java @@ -0,0 +1,12 @@ +package org.usfirst.frc.team449.robot.jacksonWrappers; + +import com.fasterxml.jackson.annotation.JsonTypeInfo; +import edu.wpi.first.wpilibj.buttons.Button; + +/** + * A jackson-compatible wrapper on WPILib's {@link Button}. + */ +@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") +public abstract class MappedButton extends Button { + +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java index d093b33f..40249105 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedDigitalInput.java @@ -18,6 +18,11 @@ public class MappedDigitalInput { */ @JsonIgnore private final List digitalInputs; + + /** + * Value of the inputs. Field to avoid garbage collection. + */ + private List digitalValues; /** * Construct a MappedDigitalInput. @@ -41,7 +46,7 @@ public MappedDigitalInput(@NotNull @JsonProperty(required = true) int[] ports) { @JsonIgnore @NotNull public List getStatus() { - List digitalValues = new ArrayList<>(); + digitalValues = new ArrayList<>(); for (DigitalInput digitalInput : digitalInputs) { //Negated because, by default, false means signal and true means no signal, and that's dumb. digitalValues.add(!digitalInput.get()); diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedJoystick.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedJoystick.java index 5206d1a6..c3fbccb0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedJoystick.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedJoystick.java @@ -5,12 +5,13 @@ import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.ObjectIdGenerators; import edu.wpi.first.wpilibj.Joystick; +import org.usfirst.frc.team449.robot.generalInterfaces.rumbleable.Rumbleable; /** * A Jackson-compatible wrapper on a {@link Joystick}. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class MappedJoystick extends Joystick { +public class MappedJoystick extends Joystick implements Rumbleable { /** * Default constructor @@ -21,4 +22,16 @@ public class MappedJoystick extends Joystick { public MappedJoystick(@JsonProperty(required = true) int port) { super(port); } + + /** + * Rumble at a given strength on each side of the device. + * + * @param left The strength to rumble the left side, on [-1, 1] + * @param right The strength to rumble the right side, on [-1, 1] + */ + @Override + public void rumble(double left, double right) { + setRumble(RumbleType.kLeftRumble, left); + setRumble(RumbleType.kRightRumble, right); + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedRunnable.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedRunnable.java new file mode 100644 index 00000000..4a4a90f0 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/jacksonWrappers/MappedRunnable.java @@ -0,0 +1,11 @@ +package org.usfirst.frc.team449.robot.jacksonWrappers; + +import com.fasterxml.jackson.annotation.JsonTypeInfo; + +/** + * A jackson-compatible wrapper on Java's {@link Runnable}. + */ +@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") +public interface MappedRunnable extends Runnable { + +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/CommandButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/CommandButton.java index cc4ef95a..ce7e25c7 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/CommandButton.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/CommandButton.java @@ -3,6 +3,7 @@ import com.fasterxml.jackson.annotation.JsonCreator; import com.fasterxml.jackson.annotation.JsonProperty; import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommand; /** @@ -18,7 +19,7 @@ public class CommandButton { * @param action The action to do to the command. */ @JsonCreator - public CommandButton(@NotNull @JsonProperty(required = true) FactoryButton button, + public CommandButton(@NotNull @JsonProperty(required = true) MappedButton button, @NotNull @JsonProperty(required = true) YamlCommand command, @NotNull @JsonProperty(required = true) Action action) { switch (action) { diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryButton.java deleted file mode 100644 index dc71fe64..00000000 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryButton.java +++ /dev/null @@ -1,50 +0,0 @@ -package org.usfirst.frc.team449.robot.oi.buttons; - -import com.fasterxml.jackson.annotation.*; -import edu.wpi.first.wpilibj.buttons.Button; -import edu.wpi.first.wpilibj.buttons.JoystickButton; -import org.jetbrains.annotations.NotNull; -import org.jetbrains.annotations.Nullable; -import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; -import org.usfirst.frc.team449.robot.oi.throttles.Throttle; - -/** - * A factory for constructing a button.. - */ -@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") -@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public abstract class FactoryButton extends Button { - - /** - * Static factory for constructing different types of buttons. - * - * @param joystick The joystick that the button is on. - * @param buttonNumber The index of the button on the joystick (starts at 1). Must be null if either triggerAxis or - * angle isn't, but otherwise must have a value. Indicates that this is a simple {@link - * JoystickButton}. - * @param triggerAxis The stick axis for the trigger that this button triggers based off of. Must be null if either - * buttonNumber or angle isn't, but otherwise must have a value. Indicates that this is a {@link - * TriggerButton}. - * @param triggerAt The amount, on [0, 1], that the joystick must be pushed to trigger. Must be null if - * triggerAxis is, and otherwise must have a value. - * @param angle The angle the D-pad needs to be pushed to to trigger this button. Must be null if either - * triggerAxis or buttonNumber isn't, but otherwise must have a value. Indicates that this is a - * {@link dPadButton}. - * @return A Button constructed from the given parameters. - */ - @NotNull - @JsonCreator - public static FactoryButton constructButton(@NotNull @JsonProperty(required = true) MappedJoystick joystick, - @Nullable Integer buttonNumber, - @Nullable Integer triggerAxis, - @Nullable Double triggerAt, - @Nullable Integer angle) { - if (triggerAxis != null) { - return new TriggerButton(new Throttle(joystick, triggerAxis, false), triggerAt); - } else if (angle != null) { - return new dPadButton(joystick, angle); - } else { - return new FactoryJoystickButton(joystick, buttonNumber); - } - } -} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryJoystickButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/SimpleButton.java similarity index 80% rename from RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryJoystickButton.java rename to RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/SimpleButton.java index 4b5a9a72..4d59cd03 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/FactoryJoystickButton.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/SimpleButton.java @@ -6,13 +6,14 @@ import com.fasterxml.jackson.annotation.ObjectIdGenerators; import edu.wpi.first.wpilibj.Joystick; import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; /** - * A version of {@link edu.wpi.first.wpilibj.buttons.JoystickButton} that is a FactoryButton. + * A version of {@link edu.wpi.first.wpilibj.buttons.JoystickButton} that is a MappedButton. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class FactoryJoystickButton extends FactoryButton { +public class SimpleButton extends MappedButton { /** * The joystick the button is on. @@ -32,8 +33,8 @@ public class FactoryJoystickButton extends FactoryButton { * @param buttonNumber The port of the button. Note that button numbers begin at 1, not 0. */ @JsonCreator - public FactoryJoystickButton(@NotNull @JsonProperty(required = true) MappedJoystick joystick, - @JsonProperty(required = true) int buttonNumber) { + public SimpleButton(@NotNull @JsonProperty(required = true) MappedJoystick joystick, + @JsonProperty(required = true) int buttonNumber) { this.joystick = joystick; this.buttonNumber = buttonNumber; } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/TriggerButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/TriggerButton.java index 8f71e760..99dc85d7 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/TriggerButton.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/TriggerButton.java @@ -5,13 +5,14 @@ import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.ObjectIdGenerators; import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton; import org.usfirst.frc.team449.robot.oi.throttles.Throttle; /** * A button that gets triggered by a specific throttle being held down at or over a certain amount. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class TriggerButton extends FactoryButton { +public class TriggerButton extends MappedButton { /** * The relevant throttle. @@ -44,6 +45,6 @@ public TriggerButton(@NotNull @JsonProperty(required = true) Throttle throttle, */ @Override public boolean get() { - return Math.abs(throttle.getValue()) >= triggerAt; + return Math.abs(throttle.getValueCached()) >= triggerAt; } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/dPadButton.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/dPadButton.java index 375fbca4..f02dacfd 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/dPadButton.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/buttons/dPadButton.java @@ -6,13 +6,14 @@ import com.fasterxml.jackson.annotation.ObjectIdGenerators; import edu.wpi.first.wpilibj.Joystick; import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; /** * A Button triggered by pushing the D-pad to a specific angle. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class dPadButton extends FactoryButton { +public class dPadButton extends MappedButton { /** * The angle that the D-pad must be pushed to to trigger this button. diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/Throttle.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/Throttle.java index 961a02bc..334654d4 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/Throttle.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/Throttle.java @@ -1,55 +1,25 @@ package org.usfirst.frc.team449.robot.oi.throttles; -import com.fasterxml.jackson.annotation.*; -import edu.wpi.first.wpilibj.Joystick; -import org.jetbrains.annotations.NotNull; -import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; +import com.fasterxml.jackson.annotation.JsonTypeInfo; +import org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable; /** - * A class representing a single axis on a joystick. + * An object representing an axis of a stick on a joystick. */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") -@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class Throttle { +public interface Throttle extends Updatable{ /** - * The stick we're using - */ - @NotNull - protected final Joystick stick; - - /** - * The axis on the joystick we care about. - */ - private final int axis; - - /** - * Whether or not the controls should be inverted - */ - private final boolean inverted; - - /** - * A basic constructor. + * Get the output of the throttle this object represents. * - * @param stick The Joystick object being used - * @param axis The axis being used. 0 is X, 1 is Y, 2 is Z. - * @param inverted Whether or not to invert the joystick input. Defaults to false. + * @return The output from [-1, 1]. */ - @JsonCreator - public Throttle(@NotNull @JsonProperty(required = true) MappedJoystick stick, - @JsonProperty(required = true) int axis, - boolean inverted) { - this.stick = stick; - this.axis = axis; - this.inverted = inverted; - } + double getValue(); /** - * Gets the raw value from the stick and inverts it if necessary. + * Get the cached output of the throttle this object represents. * - * @return The raw joystick output, on [-1, 1]. + * @return The output from [-1, 1]. */ - public double getValue() { - return (inverted ? -1 : 1) * stick.getRawAxis(axis); - } -} \ No newline at end of file + double getValueCached(); +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleBasic.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleBasic.java new file mode 100644 index 00000000..06707d7c --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleBasic.java @@ -0,0 +1,115 @@ +package org.usfirst.frc.team449.robot.oi.throttles; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import edu.wpi.first.wpilibj.Joystick; +import edu.wpi.first.wpilibj.PIDSource; +import edu.wpi.first.wpilibj.PIDSourceType; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; +import org.usfirst.frc.team449.robot.other.Clock; + +import java.util.Random; + +/** + * A class representing a single axis on a joystick. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class ThrottleBasic implements Throttle, PIDSource{ + + /** + * The stick we're using + */ + @NotNull + protected final Joystick stick; + + /** + * The axis on the joystick we care about. + */ + private final int axis; + + /** + * Whether or not the controls should be inverted + */ + private final boolean inverted; + + /** + * The cached value of the output. + */ + protected double cachedOutput; + + /** + * Default constructor. + * + * @param stick The Joystick object being used + * @param axis The axis being used. 0 is X, 1 is Y, 2 is Z. + * @param inverted Whether or not to invert the joystick input. Defaults to false. + */ + @JsonCreator + public ThrottleBasic(@NotNull @JsonProperty(required = true) MappedJoystick stick, + @JsonProperty(required = true) int axis, + boolean inverted) { + this.stick = stick; + this.axis = axis; + this.inverted = inverted; + } + + /** + * Gets the raw value from the stick and inverts it if necessary. + * + * @return The raw joystick output, on [-1, 1]. + */ + public double getValue() { + return (inverted ? -1 : 1) * stick.getRawAxis(axis); + } + + /** + * Get the cached output of the throttle this object represents. + * + * @return The output from [-1, 1]. + */ + @Override + public double getValueCached() { + return cachedOutput; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + cachedOutput = getValue(); + } + + /** + * Set which parameter of the device you are using as a process control variable. + * + * @param pidSource An enum to select the parameter. + */ + @Override + public void setPIDSourceType(PIDSourceType pidSource) { + //Do nothing + } + + /** + * Get which parameter of the device you are using as a process control variable. + * + * @return the currently selected PID source parameter + */ + @Override + public PIDSourceType getPIDSourceType() { + return null; + } + + /** + * Get the result to use in PIDController. + * + * @return the result to use in PIDController + */ + @Override + public double pidGet() { + return (inverted ? -1 : 1) * stick.getRawAxis(axis); + } +} \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleDeadbanded.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleDeadbanded.java index 3665f059..7fb6dabd 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleDeadbanded.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleDeadbanded.java @@ -1,15 +1,17 @@ package org.usfirst.frc.team449.robot.oi.throttles; import com.fasterxml.jackson.annotation.*; +import edu.wpi.first.wpilibj.filters.LinearDigitalFilter; import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; /** - * A throttle with a deadband. + * A throttle with a deadband and smoothing. */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class ThrottleDeadbanded extends Throttle { +public class ThrottleDeadbanded extends ThrottleBasic { /** * The value below which the joystick input is considered 0. @@ -26,36 +28,40 @@ public class ThrottleDeadbanded extends Throttle { */ private double sign; + /** + * The smoothing filter for this joystick. + */ + private final LinearDigitalFilter filter; + /** * A basic constructor. * * @param stick The Joystick object being used * @param axis The axis being used. 0 is X, 1 is Y, 2 is Z. * @param deadband The deadband below which the input will be read as 0, on [0, 1]. Defaults to 0. + * @param smoothingTimeSecs How many seconds of input to take into account when smoothing. Defaults to 0.02. * @param inverted Whether or not to invert the joystick input. Defaults to false. */ @JsonCreator public ThrottleDeadbanded(@NotNull @JsonProperty(required = true) MappedJoystick stick, @JsonProperty(required = true) int axis, double deadband, + @Nullable Double smoothingTimeSecs, boolean inverted) { super(stick, axis, inverted); this.deadband = deadband; + this.filter = LinearDigitalFilter.singlePoleIIR(this, smoothingTimeSecs != null ? smoothingTimeSecs : 0.02,0.02); } /** - * Gets the value from the joystick and deadbands it. The non-deadband values are scaled to avoid a discontinuity, - * so the graph of joystick input to deadbanded output looks like this: - *

- * _/ - * / + * Gets the value from the joystick and deadbands it. The non-deadband values are scaled to avoid a discontinuity. * * @return The joystick's value, after being deadbanded. */ @Override public double getValue() { //Get the smoothed value - input = super.getValue(); + input = filter.pidGet(); sign = Math.signum(input); input = Math.abs(input); diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleExponential.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleExponential.java index 9008eb30..acff7618 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleExponential.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleExponential.java @@ -5,6 +5,7 @@ import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.ObjectIdGenerators; import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; /** @@ -34,6 +35,7 @@ public class ThrottleExponential extends ThrottleDeadbanded { * @param stick The Joystick object being used * @param axis The axis being used. * @param deadband The deadband below which the input will be read as 0, on [0, 1]. Defaults to 0. + * @param smoothingTimeSecs How many seconds of input to take into account when smoothing. Defaults to 0.02. * @param inverted Whether or not to invert the joystick input. Defaults to false. * @param base The base that is raised to the power of the joystick input. */ @@ -41,9 +43,10 @@ public class ThrottleExponential extends ThrottleDeadbanded { public ThrottleExponential(@NotNull @JsonProperty(required = true) MappedJoystick stick, @JsonProperty(required = true) int axis, double deadband, + @Nullable Double smoothingTimeSecs, boolean inverted, @JsonProperty(required = true) double base) { - super(stick, axis, deadband, inverted); + super(stick, axis, deadband, smoothingTimeSecs, inverted); this.base = base; } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottlePolynomial.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottlePolynomial.java index a5c07ca7..6cb8e722 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottlePolynomial.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottlePolynomial.java @@ -5,6 +5,7 @@ import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.ObjectIdGenerators; import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; import org.usfirst.frc.team449.robot.other.Polynomial; @@ -26,17 +27,18 @@ public class ThrottlePolynomial extends ThrottleDeadbanded { * @param stick The Joystick object being used * @param axis The axis being used. 0 is X, 1 is Y, 2 is Z. * @param deadband The deadband below which the input will be read as 0, on [0, 1]. Defaults to 0. + * @param smoothingTimeSecs How many seconds of input to take into account when smoothing. Defaults to 0.02. * @param inverted Whether or not to invert the joystick input. Defaults to false. - * @param polynomial The polynomially that scales the throttle. Must not have any negative - * exponents. + * @param polynomial The polynomially that scales the throttle. Must not have any negative exponents. */ @JsonCreator public ThrottlePolynomial(@NotNull @JsonProperty(required = true) MappedJoystick stick, @JsonProperty(required = true) int axis, double deadband, + @Nullable Double smoothingTimeSecs, boolean inverted, @NotNull @JsonProperty(required = true) Polynomial polynomial) { - super(stick, axis, deadband, inverted); + super(stick, axis, deadband, smoothingTimeSecs, inverted); //Check for negative exponents for (Double power : polynomial.getPowerToCoefficientMap().keySet()) { diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleSum.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleSum.java new file mode 100644 index 00000000..7c7d0446 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/throttles/ThrottleSum.java @@ -0,0 +1,80 @@ +package org.usfirst.frc.team449.robot.oi.throttles; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import org.jetbrains.annotations.NotNull; + +/** + * A Throttle that sums any number of other Throttles. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class ThrottleSum implements Throttle { + + /** + * The throttles to sum. + */ + @NotNull + protected final Throttle[] throttles; + + /** + * The cached output. + */ + protected double cachedValue; + + /** + * The sum. Field to avoid garbage collection. + */ + private double sum; + + /** + * Default constructor. + * + * @param throttles The throttles to sum. + */ + @JsonCreator + public ThrottleSum(@NotNull @JsonProperty(required = true) Throttle[] throttles) { + this.throttles = throttles; + } + + /** + * Sums the throttles and returns their output + * + * @return The summed outputs, clipped to [-1, 1]. + */ + public double getValue() { + //sum throttles + sum = 0; + for (Throttle throttle : throttles) { + sum += throttle.getValue(); + } + + //clip to [-1, 1] + if (sum >= 1) { + return 1; + } else if (sum <= -1) { + return -1; + } else { + return sum; + } + } + + /** + * Get the cached output of the throttle this object represents. + * + * @return The output from [-1, 1]. + */ + @Override + public double getValueCached() { + return cachedValue; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + cachedValue = getValue(); + } +} \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java index b0f16d45..c0073b9e 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIOutreach.java @@ -4,8 +4,10 @@ import com.fasterxml.jackson.annotation.JsonIdentityInfo; import com.fasterxml.jackson.annotation.JsonProperty; import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import edu.wpi.first.wpilibj.buttons.Button; import org.jetbrains.annotations.NotNull; -import org.usfirst.frc.team449.robot.oi.buttons.FactoryButton; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton; + @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) public class OIOutreach implements OIUnidirectional { @@ -26,12 +28,22 @@ public class OIOutreach implements OIUnidirectional { * A button that overrides the lower priority controller */ @NotNull - private final FactoryButton button; + private final Button button; + + /** + * The cached outputs for the left and right sides of the drive. + */ + private double cachedLeftOutput, cachedRightOutput; + + /** + * Whether the driver was trying to drive straight when values were cached. + */ + private boolean cachedCommandingStraight; @JsonCreator public OIOutreach(@NotNull @JsonProperty(required = true) OIUnidirectional overridingOI, @NotNull @JsonProperty(required = true) OIUnidirectional overridenOI, - @NotNull @JsonProperty(required = true) FactoryButton button) { + @NotNull @JsonProperty(required = true) MappedButton button) { this.overridingOI = overridingOI; this.overridenOI = overridenOI; this.button = button; @@ -74,4 +86,44 @@ public double getRightOutput() { public boolean commandingStraight() { return getLeftOutput() == getRightOutput(); } + + /** + * The cached output to be given to the left side of the drive. + * + * @return Output to left side from [-1, 1] + */ + @Override + public double getLeftOutputCached() { + return cachedLeftOutput; + } + + /** + * The cached output to be given to the right side of the drive. + * + * @return Output to right side from [-1, 1] + */ + @Override + public double getRightOutputCached() { + return cachedRightOutput; + } + + /** + * Whether the driver was trying to drive straight when values were cached. + * + * @return True if the driver is trying to drive straight, false otherwise. + */ + @Override + public boolean commandingStraightCached() { + return cachedCommandingStraight; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + cachedLeftOutput = getLeftOutput(); + cachedRightOutput = getRightOutput(); + cachedCommandingStraight = cachedLeftOutput == cachedRightOutput; + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIUnidirectional.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIUnidirectional.java index c95a332a..beecbc41 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIUnidirectional.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/OIUnidirectional.java @@ -1,6 +1,7 @@ package org.usfirst.frc.team449.robot.oi.unidirectional; import com.fasterxml.jackson.annotation.JsonTypeInfo; +import org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable; import org.usfirst.frc.team449.robot.oi.OI; /** @@ -8,7 +9,7 @@ * holonomic) */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") -public interface OIUnidirectional extends OI{ +public interface OIUnidirectional extends Updatable, OI { /** * The output to be given to the left side of the drive. @@ -30,4 +31,25 @@ public interface OIUnidirectional extends OI{ * @return True if the driver is trying to drive straight, false otherwise. */ boolean commandingStraight(); + + /** + * The cached output to be given to the left side of the drive. + * + * @return Output to left side from [-1, 1] + */ + double getLeftOutputCached(); + + /** + * The cached output to be given to the right side of the drive. + * + * @return Output to right side from [-1, 1] + */ + double getRightOutputCached(); + + /** + * Whether the driver was trying to drive straight when values were cached. + * + * @return True if the driver is trying to drive straight, false otherwise. + */ + boolean commandingStraightCached(); } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java index 0ac47cac..3ed14c45 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcade.java @@ -9,6 +9,16 @@ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") public abstract class OIArcade implements OIUnidirectional { + /** + * Cached output values. + */ + private double rotCached, fwdCached, leftCached, rightCached; + + /** + * Whether the driver was trying to drive straight when values were cached. + */ + private boolean commandingStraightCached; + /** * Get the rotational input. * @@ -23,6 +33,24 @@ public abstract class OIArcade implements OIUnidirectional { */ public abstract double getFwd(); + /** + * Get the cached rotational input. + * + * @return rotational velocity component from [-1, 1], where 1 is right and -1 is left. + */ + public double getRotCached(){ + return rotCached; + } + + /** + * Get the cached velocity input. + * + * @return forward velocity component from [-1, 1], where 1 is forwards and -1 is backwards + */ + public double getFwdCached(){ + return fwdCached; + } + /** * The output to be given to the left side of the drive. * @@ -50,4 +78,44 @@ public double getRightOutput() { public boolean commandingStraight() { return getRot() == 0; } + + /** + * The cached output to be given to the left side of the drive. + * + * @return Output to left side from [-1, 1] + */ + public double getLeftOutputCached(){ + return leftCached; + } + + /** + * The cached output to be given to the right side of the drive. + * + * @return Output to right side from [-1, 1] + */ + public double getRightOutputCached(){ + return rightCached; + } + + /** + * Whether the driver was trying to drive straight when values were cached. + * + * @return True if the driver is trying to drive straight, false otherwise. + */ + @Override + public boolean commandingStraightCached(){ + return commandingStraightCached; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + rotCached = getRot(); + fwdCached = getFwd(); + commandingStraightCached = commandingStraight(); + leftCached = fwdCached + rotCached; + rightCached = fwdCached - rotCached; + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java index 603745e1..30c3dab0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/arcade/OIArcadeWithDPad.java @@ -7,15 +7,17 @@ import edu.wpi.first.wpilibj.Joystick; import org.jetbrains.annotations.NotNull; import org.jetbrains.annotations.Nullable; +import org.usfirst.frc.team449.robot.generalInterfaces.loggable.Loggable; import org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick; import org.usfirst.frc.team449.robot.oi.throttles.Throttle; +import org.usfirst.frc.team449.robot.other.Clock; import org.usfirst.frc.team449.robot.other.Polynomial; /** * An arcade OI with an option to use the D-pad for turning. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class OIArcadeWithDPad extends OIArcade { +public class OIArcadeWithDPad extends OIArcade implements Loggable { /** * How much the D-pad moves the robot rotationally on a 0 to 1 scale, equivalent to pushing the turning stick that @@ -82,7 +84,7 @@ public OIArcadeWithDPad( this.scaleRotByFwdPoly = scaleRotByFwdPoly; this.turnInPlaceRotScale = turnInPlaceRotScale; } - + /** * The output of the throttle controlling linear velocity, smoothed and adjusted according to what type of joystick * it is. @@ -91,7 +93,6 @@ public OIArcadeWithDPad( */ @Override public double getFwd() { - //Scale based on rotational throttle for more responsive turning at high speed return fwdThrottle.getValue(); } @@ -107,17 +108,51 @@ public double getRot() { if (gamepad != null && !(gamepad.getPOV() == -1 || gamepad.getPOV() % 180 == 0)) { //Output the shift value return gamepad.getPOV() < 180 ? dPadShift : -dPadShift; - } else { - //Return the throttle value if it's outside of the deadband. - if (fwdThrottle.getValue() == 0) { - return rotThrottle.getValue() * turnInPlaceRotScale; - } else { - if (scaleRotByFwdPoly != null) { - return rotThrottle.getValue() * scaleRotByFwdPoly.get(Math.abs(fwdThrottle.getValue())); - } else { - return rotThrottle.getValue(); - } - } + } else if (getFwd() == 0) { //Turning in place + return rotThrottle.getValue() * turnInPlaceRotScale; + } else if (scaleRotByFwdPoly != null) { //If we're using Cheezy Drive + return rotThrottle.getValue() * scaleRotByFwdPoly.get(Math.abs(getFwd())); + } else { //Plain and simple + return rotThrottle.getValue(); } } + + /** + * Get the headers for the data this subsystem logs every loop. + * + * @return An N-length array of String labels for data, where N is the length of the Object[] returned by getData(). + */ + @NotNull + @Override + public String[] getHeader() { + return new String[]{ + "Fwd", + "Rot" + }; + } + + /** + * Get the data this subsystem logs every loop. + * + * @return An N-length array of Objects, where N is the number of labels given by getHeader. + */ + @NotNull + @Override + public Object[] getData() { + return new Object[]{ + getFwd(), + getRot() + }; + } + + /** + * Get the name of this object. + * + * @return A string that will identify this object in the log file. + */ + @NotNull + @Override + public String getName() { + return "OI"; + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java index 58290d10..1aa1dc93 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITank.java @@ -9,6 +9,11 @@ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") public abstract class OITank implements OIUnidirectional { + /** + * Cached left and right throttle values. + */ + private double leftThrottleCached, rightThrottleCached; + /** * Get the throttle for the left side of the drive. * @@ -23,6 +28,24 @@ public abstract class OITank implements OIUnidirectional { */ public abstract double getRightThrottle(); + /** + * Get the cached throttle for the left side of the drive. + * + * @return percent of max speed for left motor cluster from [-1.0, 1.0] + */ + public double getLeftThrottleCached(){ + return leftThrottleCached; + } + + /** + * Get the cached throttle for the right side of the drive. + * + * @return percent of max speed for right motor cluster from [-1.0, 1.0] + */ + public double getRightThrottleCached(){ + return rightThrottleCached; + } + /** * The output to be given to the left side of the drive. * @@ -40,4 +63,31 @@ public double getLeftOutput() { public double getRightOutput() { return getRightThrottle(); } + + /** + * The cached output to be given to the left side of the drive. + * + * @return Output to left side from [-1, 1] + */ + public double getLeftOutputCached(){ + return leftThrottleCached; + } + + /** + * The cached output to be given to the right side of the drive. + * + * @return Output to right side from [-1, 1] + */ + public double getRightOutputCached(){ + return rightThrottleCached; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + leftThrottleCached = getLeftThrottle(); + rightThrottleCached = getRightThrottle(); + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITankSimple.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITankSimple.java index 136a7585..ff32ca11 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITankSimple.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/oi/unidirectional/tank/OITankSimple.java @@ -25,6 +25,11 @@ public class OITankSimple extends OITank { @NotNull private final Throttle rightThrottle; + /** + * Whether the driver was trying to drive straight when values were cached. + */ + private boolean commandingStraightCached; + /** * The difference between left and right input within which the driver is considered to be trying to drive * straight. @@ -85,4 +90,20 @@ public double getRightThrottle() { public boolean commandingStraight() { return Math.abs(leftThrottle.getValue() - rightThrottle.getValue()) <= commandingStraightTolerance; } + + /** + * Whether the driver was trying to drive straight when values were cached. + * + * @return True if the driver is trying to drive straight, false otherwise. + */ + @Override + public boolean commandingStraightCached() { + return commandingStraightCached; + } + + @Override + public void update(){ + commandingStraightCached = commandingStraight(); + super.update(); + } } \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Clock.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Clock.java index e93b5e59..53f3310b 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Clock.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Clock.java @@ -20,19 +20,20 @@ public class Clock { /** * Make constructor private so it can't be called */ - private Clock(){} + private Clock() { + } /** * Updates the current time. */ - public synchronized static void updateTime(){ - currentTime = System.currentTimeMillis()-startTime; + public synchronized static void updateTime() { + currentTime = System.currentTimeMillis() - startTime; } /** * Sets the start time to the current time. */ - public synchronized static void setStartTime(){ + public synchronized static void setStartTime() { startTime = System.currentTimeMillis(); } @@ -40,7 +41,7 @@ public synchronized static void setStartTime(){ * @return The time since the start time, in milliseconds. */ @Contract(pure = true) - public synchronized static long currentTimeMillis(){ + public synchronized static long currentTimeMillis() { return currentTime; } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Logger.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Logger.java index 678c737e..7cd674dd 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Logger.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Logger.java @@ -92,7 +92,7 @@ public Logger(@NotNull @JsonProperty(required = true) Loggable[] subsystems, FileWriter eventLogWriter = new FileWriter(this.eventLogFilename); FileWriter telemetryLogWriter = new FileWriter(this.telemetryLogFilename); //Write the file headers - eventLogWriter.write("time,class,message"); + eventLogWriter.write("time,class,message" + "\n"); //We use a StringBuilder because it's better for building up a string via concatenation. StringBuilder telemetryHeader = new StringBuilder(); telemetryHeader.append("time,"); @@ -112,7 +112,7 @@ public Logger(@NotNull @JsonProperty(required = true) Loggable[] subsystems, //Delete the trailing comma telemetryHeader.deleteCharAt(telemetryHeader.length() - 1); - telemetryHeader.append("\n"); + telemetryHeader.append(",\n"); //Write the telemetry file header telemetryLogWriter.write(telemetryHeader.toString()); eventLogWriter.close(); @@ -201,10 +201,13 @@ public void run() { telemetryData.append(","); } } - telemetryData.append("\n"); + + String telemetryString = telemetryData.toString(); + telemetryString = telemetryString.substring(0, telemetryString.length() - 1); + telemetryString += "\n"; //Log the data to a file. try { - telemetryLogWriter.write(telemetryData.toString()); + telemetryLogWriter.write(telemetryString); } catch (IOException e) { System.out.println("Logging failed!"); e.printStackTrace(); diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/MotionProfileData.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/MotionProfileData.java index b74dba9a..af0e1b5d 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/MotionProfileData.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/MotionProfileData.java @@ -28,17 +28,19 @@ public class MotionProfileData { private final boolean velocityOnly; /** - * A 2D array containing 3 values for each point- position, velocity, and delta time respectively. + * A 2D array containing 4 values for each point- position, velocity, acceleration and delta time respectively, in + * feet, feet per second, feet per (second^2), and milliseconds. */ private double data[][]; /** * Default constructor * - * @param filename The filename of the .csv with the motion profile data. The first line must be the number of other - * lines. + * @param filename The filename of the .csv with the motion profile data. The first line must be the number of + * other lines. * @param inverted Whether or not the profile is inverted (would be inverted if we're driving it backwards) - * @param velocityOnly Whether or not to only use velocity feed-forward. Used for tuning kV and kA. Defaults to false. + * @param velocityOnly Whether or not to only use velocity feed-forward. Used for tuning kV and kA. Defaults to + * false. */ @JsonCreator public MotionProfileData(@NotNull @JsonProperty(required = true) String filename, @@ -46,6 +48,7 @@ public MotionProfileData(@NotNull @JsonProperty(required = true) String filename boolean velocityOnly) { this.inverted = inverted; this.velocityOnly = velocityOnly; + try { readFile(Robot.RESOURCES_PATH + filename); } catch (IOException e) { @@ -65,7 +68,7 @@ private void readFile(@NotNull String filename) throws IOException { int numLines = Integer.parseInt(br.readLine()); //Instantiate data - data = new double[numLines][3]; + data = new double[numLines][4]; //Declare the arrays outside the loop to avoid garbage collection. String[] line; @@ -76,19 +79,14 @@ private void readFile(@NotNull String filename) throws IOException { //split up the line line = br.readLine().split(",\t"); //declare as a new double because we already put the old object it referenced in data. - tmp = new double[3]; - - //Invert the position and velocity if the profile is inverted - if (inverted) { - tmp[0] = -Double.parseDouble(line[0]); - tmp[1] = -Double.parseDouble(line[1]); - } else { - tmp[0] = Double.parseDouble(line[0]); - tmp[1] = Double.parseDouble(line[1]); - } - - //Trim the end of line comma - tmp[2] = Double.parseDouble(line[2].replace(",", "")); + tmp = new double[4]; + + tmp[0] = Double.parseDouble(line[0]); + tmp[1] = Double.parseDouble(line[1]); + tmp[2] = Double.parseDouble(line[2]); + + //Convert to milliseconds + tmp[3] = Double.parseDouble(line[3]) * 1000; data[i] = tmp; } //Close the reader @@ -109,4 +107,11 @@ public double[][] getData() { public boolean isVelocityOnly() { return velocityOnly; } + + /** + * @return Whether or not the profile is inverted because we're driving it backwards. + */ + public boolean isInverted() { + return inverted; + } } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java new file mode 100644 index 00000000..9ff17c70 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/UnidirectionalPoseEstimator.java @@ -0,0 +1,456 @@ +package org.usfirst.frc.team449.robot.other; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import org.jetbrains.annotations.NotNull; +import org.jetbrains.annotations.Nullable; +import org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional; +import org.usfirst.frc.team449.robot.generalInterfaces.loggable.Loggable; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; + +import java.util.ArrayList; +import java.util.List; + +/** + * A Runnable for pose estimation that can take absolute positions. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class UnidirectionalPoseEstimator implements MappedRunnable, Loggable { + + /** + * The wheel-to-wheel diameter of the robot, in feet. + */ + @Nullable + private final Double robotDiameter; + + /** + * The subsystem to get gyro and encoder data from. + */ + @NotNull + private final T subsystem; + + /** + * The maximum amount, in degrees, a new absolute position's angle can be off from the gyro reading and still be + * accepted as valid. + */ + private final double absolutePosAngleTolerance; + + /** + * A list of all the gyro angles recorded, in order from oldest to newest and in degrees. + */ + @NotNull + private List angles; + + /** + * A list of all [x,y] transformation vectors calculated, in order from oldest to newest and in feet. + */ + @NotNull + private List vectors; + + /** + * A list of all the times at which the gyro angles and vectors were recorded, in order from oldest to newest and in + * milliseconds. + */ + @NotNull + private List times; + + /** + * The current x,y position of the robot, in feet. + */ + private double[] currentPos; + + /** + * The time, in milliseconds since the robot code started, that the last absolute position was recorded at. + */ + private long absolutePosTime; + + /** + * The encoder reading of the left encoder the last time the loop ran, in feet. + */ + private double lastLeftPos; + + /** + * The encoder reading of the right encoder the last time the loop ran, in feet. + */ + private double lastRightPos; + + /** + * The angle of the gyro the last time the loop ran, in degrees. This is normally the same as the last element of + * angles, but it's possible that a new absolute position could erase all elements of angles. + */ + private double lastTheta; + + /** + * The last time the loop ran, in milliseconds. This is normally the same as the last element of times, but it's + * possible that a new absolute position could erase all elements of times. + */ + private long lastTime; + + /** + * The most recently calculated effective wheelbase diameter (from the Eli method), in feet. + */ + private double fudgedWheelbaseDiameter; + + /** + * Whether or not the left side was re-calculated last tic using the Noah method. + */ + private boolean recalcedLeft; + + /** + * The percent the Noah method changed the wrong encoder reading by. + */ + private double percentChanged; + + /** + * Angle and magnitude of vector being calculated. Field to avoid garbage collection. + */ + private double vectorAngle, vectorMagnitude; + + /** + * Per-run variables for run(). Fields to avoid garbage collection. + */ + private double left, right, theta, deltaLeft, deltaRight, deltaTheta; + private long time; + + /** + * Output vector from run(). Field to avoid garbage collection. + */ + private double[] vector; + + /** + * Default constructor. + * + * @param robotDiameter The wheel-to-wheel diameter of the robot, in feet. + * @param subsystem The subsystem to get gyro and encoder data from. + * @param absolutePosAngleTolerance The maximum amount, in degrees, a new absolute position's angle can be off from + * the gyro reading and still be accepted as valid. + * @param startX The starting X of the robot, in feet. Defaults to 0. + * @param startY The starting Y of the robot, in feet. Defaults to 0. + * @param startTheta The starting angle of the robot, in degrees. Defaults to 0. + */ + @JsonCreator + public UnidirectionalPoseEstimator(@Nullable Double robotDiameter, + @JsonProperty(required = true) @NotNull T subsystem, + @JsonProperty(required = true) double absolutePosAngleTolerance, + double startX, + double startY, + double startTheta) { + this.robotDiameter = robotDiameter; + this.subsystem = subsystem; + this.absolutePosAngleTolerance = absolutePosAngleTolerance; + lastTheta = startTheta; + + //Construct lists + angles = new ArrayList<>(); + vectors = new ArrayList<>(); + times = new ArrayList<>(); + + //Set up start pos + currentPos = new double[2]; + currentPos[0] = startX; + currentPos[1] = startY; + + lastLeftPos = subsystem.getLeftPos(); + lastRightPos = subsystem.getRightPos(); + absolutePosTime = 0; + lastTime = 0; + } + + @NotNull + private double[] calcEliVector(double left, double right, double deltaTheta, double lastAngle) { + + //If we're going in a straight line + if (deltaTheta == 0) { + //we could use deltaRight here, doesn't matter. Going straight means no change in angle and left and right are the same. + return new double[]{left * Math.cos(lastAngle), left * Math.sin(lastAngle)}; + } else { + //This next part is too complicated to explain in comments. Read this wiki page instead: + // http://team449.shoutwiki.com/wiki/Pose_Estimation + vectorAngle = lastAngle + deltaTheta / 2.; + vectorMagnitude = 2. * ((left + right) / 2.) / deltaTheta * Math.sin(deltaTheta / 2.); + return new double[]{vectorMagnitude * Math.cos(vectorAngle), vectorMagnitude * Math.sin(vectorAngle)}; + } + } + + @NotNull + private double[] calcVector(double left, double right, double robotDiameter, double deltaTheta, double lastAngle) { + + //If we're going in a straight line + if (deltaTheta == 0) { + //we could use deltaRight here, doesn't matter. Going straight means no change in angle and left and right are the same. + return new double[]{left * Math.cos(lastAngle), left * Math.sin(lastAngle)}; + } else { + //This next part is too complicated to explain in comments. Read this wiki page instead: + // http://team449.shoutwiki.com/wiki/Pose_Estimation + if (left - right == 0) { + vectorMagnitude = 2* left / deltaTheta * Math.sin(deltaTheta / 2.); + } else { + vectorMagnitude = 2* robotDiameter / 2. * (left + right) / (left - right) * Math.sin(deltaTheta / 2.); + } + vectorAngle = lastAngle + deltaTheta / 2.; + return new double[]{vectorMagnitude * Math.cos(vectorAngle), vectorMagnitude * Math.sin(vectorAngle)}; + } + } + + /** + * Use the current gyro and encoder data to calculate how the robot has moved since the last time run was called. + */ + @Override + public synchronized void run() { + //Record everything at the start, as it may change between executing lines of code and that would be bad. + left = subsystem.getLeftPos(); + right = subsystem.getRightPos(); + theta = Math.toRadians(subsystem.getAngularDisplacement()); + time = Clock.currentTimeMillis(); + + //Calculate differences versus the last measurement + deltaLeft = left - lastLeftPos; + deltaRight = right - lastRightPos; + deltaTheta = theta - lastTheta; + if (deltaTheta == 0) { + fudgedWheelbaseDiameter = -1; + } else { + fudgedWheelbaseDiameter = (deltaLeft - deltaRight) / deltaTheta; + } + + if (robotDiameter != null) { + //Noah's Approach: + + //For this next part, we assume that the gyro is 100% accurate at measuring the change in angle over the given + + //time period and that the encoders will possibly overmeasure (due to wheel slip) but never undermeasure. + //Given those constraints, we have an overdetermined system because deltaTheta should be equal to + //(deltaLeft-deltaRight)/robotDiameter. We can use this to determine which wheel slipped more, and replace its + //reading with a value calculated from the other encoder and the gyro. + if (deltaTheta < (deltaLeft - deltaRight) / robotDiameter) { + if (deltaLeft > 0) { + percentChanged = ((deltaRight + robotDiameter * deltaTheta) - deltaLeft) / deltaLeft; + deltaLeft = deltaRight + robotDiameter * deltaTheta; + recalcedLeft = true; + } else { + percentChanged = ((deltaLeft - robotDiameter * deltaTheta) - deltaRight) / deltaRight; + deltaRight = deltaLeft - robotDiameter * deltaTheta; + recalcedLeft = false; + } + } else if (deltaTheta > (deltaLeft - deltaRight) / robotDiameter) { + if (deltaLeft < 0) { + percentChanged = ((deltaRight + robotDiameter * deltaTheta) - deltaLeft) / deltaLeft; + deltaLeft = deltaRight + robotDiameter * deltaTheta; + recalcedLeft = true; + } else { + percentChanged = ((deltaLeft - robotDiameter * deltaTheta) - deltaRight) / deltaRight; + deltaRight = deltaLeft - robotDiameter * deltaTheta; + recalcedLeft = false; + } + } + vector = calcVector(deltaLeft, deltaRight, robotDiameter, deltaTheta, lastTheta); + } else { + + //Eli's Approach + + //Here we assume all the measured values are correct and adjust the diameter to match. + vector = calcEliVector(deltaLeft, deltaRight, deltaTheta, lastTheta); + } + + //The vector for how much the robot moves, element 0 is x and element 1 is y. + + //If we received an absolute position between the last run and this one, scale the vector so it only includes + //the change since the absolute position was given + if (absolutePosTime > lastTime) { + currentPos[0] += vector[0] * (time - absolutePosTime) / (time - lastTime); + currentPos[1] += vector[1] * (time - absolutePosTime) / (time - lastTime); + } else { + currentPos[0] += vector[0]; + currentPos[1] += vector[1]; + } + + //record measurements in lists + vectors.add(vector); + angles.add(theta); + times.add(time); + + //record current stuff as "last" + lastTheta = theta; + lastRightPos = right; + lastLeftPos = left; + lastTime = time; + } + + /** + * Add an absolute position at the given time stamp. + * + * @param x The absolute x, in feet + * @param y The absolute y, in feet + * @param time The time, in milleseconds after the robot code started, that the absolute position was recorded. + * @return true if the absolute position was the most recent received and was used, false otherwise. + */ + public synchronized boolean addAbsolutePos(double x, double y, long time) { + //Ignore it if it's older than the existing absolute position + if (time < absolutePosTime) { + return false; + } + + //Add the given position + addPos(x, y, time, getFirstKeepableIndex(time)); + return true; + } + + /** + * Add an absolute position at the given time stamp, using an angle measured to verify that the absolute position is + * correct. + * + * @param x The absolute x, in feet + * @param y The absolute y, in feet + * @param time The time, in milleseconds after the robot code started, that the absolute position was recorded + * @param angle The absolute angle, in degrees. + * @return true if the absolute position was the most recent received and the angle was correct enough to be used, + * false otherwise. + */ + public synchronized boolean addAbsolutePos(double x, double y, long time, double angle) { + //Ignore it if it's older than the existing absolute position + if (time < absolutePosTime) { + return false; + } + + //Get the first keepable index + int firstKeepableIndex = getFirstKeepableIndex(time); + + //Find the angle of the gyro at the time the absolute position was recorded + double angleAtTime; + if (firstKeepableIndex == 0) { + //If the absolute position is from before the first angle was recorded, just use the first angle. + angleAtTime = angles.get(0); + } else { + //Calculate the angle at the time by assuming constant angular velocity over the interval. + angleAtTime = (angles.get(firstKeepableIndex - 1) * (time - times.get(firstKeepableIndex - 1)) + + angles.get(firstKeepableIndex) * (times.get(firstKeepableIndex) - time)) + / (times.get(firstKeepableIndex) - times.get(firstKeepableIndex - 1)); + } + + //If the angle from the gyro and from the absolute position are too different, don't use the absolute position. + if (Math.abs(angleAtTime - angle) > absolutePosAngleTolerance) { + return false; + } else { + //Otherwise, use it. + addPos(x, y, time, firstKeepableIndex); + return true; + } + } + + /** + * Get the current absolute position of the robot + * + * @return The current x,y position in feet. + */ + public double[] getPos() { + return currentPos; + } + + /** + * An internal helper method that adds an absolute position given a first keepable index. + * + * @param x The absolute x, in feet + * @param y The absolute y, in feet + * @param time The time, in milleseconds after the robot code started, that the absolute position was + * recorded + * @param firstKeepableIndex The first index of the times, vectors, and angles arrays recorded after the given + * time. + */ + private void addPos(double x, double y, long time, int firstKeepableIndex) { + this.absolutePosTime = time; + this.currentPos = new double[2]; + this.currentPos[0] = x; + this.currentPos[1] = y; + + //The "first keepable" vector starts before the absolute position is measured and ends after it, so we have to + //add the part that comes after to the position. + if (firstKeepableIndex > 0) { //This if is just to prevent IndexOutOfBounds on times.get(firstKeepableIndex - 1) + this.currentPos[0] += vectors.get(firstKeepableIndex)[0] * (times.get(firstKeepableIndex) - time) / + (times.get(firstKeepableIndex) - times.get(firstKeepableIndex - 1)); + this.currentPos[1] += vectors.get(firstKeepableIndex)[1] * (times.get(firstKeepableIndex) - time) / + (times.get(firstKeepableIndex) - times.get(firstKeepableIndex - 1)); + } + + //Trim vectors to only be the relevant vectors. + vectors = vectors.subList(firstKeepableIndex, vectors.size()); + + //Add all the vectors that come after the absolutePos to the position. Loop starts at index 1 because index 0, + //the firstKeepableIndex, we already accounted for above. + for (int i = 1; i < vectors.size(); i++) { + currentPos[0] += vectors.get(i)[0]; + currentPos[1] += vectors.get(i)[1]; + } + + //Trim other lists + times = times.subList(firstKeepableIndex, times.size()); + angles = angles.subList(firstKeepableIndex, angles.size()); + } + + /** + * Finds the first index of the times array that was recorded after the given time. + * + * @param time A time in milliseconds since the robot code started + * @return the lowest index of times whose value is greater than time. + */ + private int getFirstKeepableIndex(long time) { + int firstKeepableIndex = times.size(); + for (int i = 0; i < times.size(); i++) { + if (times.get(i) > time) { + firstKeepableIndex = i; + break; + } + } + return firstKeepableIndex; + } + + /** + * Get the headers for the data this subsystem logs every loop. + * + * @return An N-length array of String labels for data, where N is the length of the Object[] returned by getData(). + */ + @NotNull + @Override + public String[] getHeader() { + return new String[]{ + "effective_wheelbase", + "recalced_left", + "percent_changed", + "x_displacement", + "y_displacement" + }; + } + + /** + * Get the data this subsystem logs every loop. + * + * @return An N-length array of Objects, where N is the number of labels given by getHeader. + */ + @NotNull + @Override + public Object[] getData() { + return new Object[]{ + fudgedWheelbaseDiameter, + recalcedLeft, + percentChanged, + getPos()[0], + getPos()[1] + }; + } + + /** + * Get the name of this object. + * + * @return A string that will identify this object in the log file. + */ + @NotNull + @Override + public String getName() { + if (robotDiameter != null) { + return "NoahPoseEstimator"; + } + return "EliPoseEstimator"; + } +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Updater.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Updater.java new file mode 100644 index 00000000..0d2c81b3 --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/other/Updater.java @@ -0,0 +1,42 @@ +package org.usfirst.frc.team449.robot.other; + +import com.fasterxml.jackson.annotation.JsonCreator; +import com.fasterxml.jackson.annotation.JsonIdentityInfo; +import com.fasterxml.jackson.annotation.JsonProperty; +import com.fasterxml.jackson.annotation.ObjectIdGenerators; +import org.jetbrains.annotations.NotNull; +import org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable; +import org.usfirst.frc.team449.robot.jacksonWrappers.MappedRunnable; + +/** + * A Runnable for updating cached variables. + */ +@JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) +public class Updater implements MappedRunnable{ + + /** + * The objects to update. + */ + @NotNull + private final Updatable[] updatables; + + /** + * Default constructor + * + * @param updatables The objects to update. + */ + @JsonCreator + public Updater(@NotNull @JsonProperty(required = true) Updatable[] updatables) { + this.updatables = updatables; + } + + /** + * Update all the updatables. + */ + @Override + public void run() { + for (Updatable updatable : updatables){ + updatable.update(); + } + } +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java index ce70df12..f64ea714 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/climber/ClimberCurrentLimited.java @@ -48,6 +48,11 @@ public class ClimberCurrentLimited extends YamlSubsystem implements Loggable, Su */ private boolean motorSpinning; + /** + * Whether the condition was met last time caching was done. + */ + private boolean conditionMetCached; + /** * Default constructor @@ -164,4 +169,20 @@ public boolean isMotorOn() { public boolean isConditionTrue() { return powerLimitTimer.get(Math.abs(canTalonSRX.getOutputCurrent() * canTalonSRX.getOutputVoltage()) > maxPower); } + + /** + * @return true if the condition was met when cached, false otherwise + */ + @Override + public boolean isConditionTrueCached() { + return conditionMetCached; + } + + /** + * Updates all cached values with current ones. + */ + @Override + public void update() { + conditionMetCached = isConditionTrue(); + } } \ No newline at end of file diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/intake/IntakeFixedAndActuated.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/intake/IntakeFixedAndActuated.java index f1a684de..44d51aef 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/intake/IntakeFixedAndActuated.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/intake/IntakeFixedAndActuated.java @@ -67,10 +67,10 @@ public class IntakeFixedAndActuated extends YamlSubsystem implements SubsystemSo /** * Default constructor. * - * @param fixedMotor The SimpleMotor powering the fixed intake. + * @param fixedMotor The SimpleMotor powering the fixed intake. * @param fixedAgitateSpeed The speed to run the fixed victor at to agitate balls, on [-1, 1] * @param fixedIntakeSpeed The speed to run the fixed victor to intake balls, on [-1, 1] - * @param actuatedMotor The SimpleMotor powering the actuated intake. + * @param actuatedMotor The SimpleMotor powering the actuated intake. * @param actuatedSpeed The speed to run the actuated victor to intake balls, on [-1, 1]. * @param piston The piston for raising and lowering the actuated intake. */ diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java index 086e10e9..42d2fbff 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/complex/shooter/LoggingShooter.java @@ -55,7 +55,7 @@ public class LoggingShooter extends YamlSubsystem implements Loggable, Subsystem * * @param shooterTalon The TalonSRX controlling the flywheel. * @param shooterThrottle The throttle, from [-1, 1], at which to run the multiSubsystem. - * @param feederMotor The motor controlling the feeder. + * @param feederMotor The motor controlling the feeder. * @param feederThrottle The throttle, from [-1, 1], at which to run the feeder. * @param spinUpTimeSecs The amount of time, in seconds, it takes for the multiSubsystem to get up to speed. * Defaults to 0. @@ -120,7 +120,7 @@ public Object[] getData() { @NotNull @Override public String getName() { - return "multiSubsystem"; + return "loggingShooter"; } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/binaryMotor/commands/TurnMotorOffWithRequires.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/binaryMotor/commands/TurnMotorOffWithRequires.java index f05ae9ec..64b28f6a 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/binaryMotor/commands/TurnMotorOffWithRequires.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/binaryMotor/commands/TurnMotorOffWithRequires.java @@ -14,7 +14,7 @@ * controlling the subsystem. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class TurnMotorOffWithRequires extends TurnMotorOff { +public class TurnMotorOffWithRequires extends TurnMotorOff { /** * Default constructor diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/conditional/SubsystemConditional.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/conditional/SubsystemConditional.java index 308ac78c..ea3faea0 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/conditional/SubsystemConditional.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/conditional/SubsystemConditional.java @@ -1,15 +1,21 @@ package org.usfirst.frc.team449.robot.subsystem.interfaces.conditional; import com.fasterxml.jackson.annotation.JsonTypeInfo; +import org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable; /** * A subsystem with a condition that's sometimes met, e.g. a limit switch, a current/power limit, an IR sensor. */ @JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT, property = "@class") -public interface SubsystemConditional { +public interface SubsystemConditional extends Updatable{ /** * @return true if the condition is met, false otherwise */ boolean isConditionTrue(); + + /** + * @return true if the condition was met when cached, false otherwise + */ + boolean isConditionTrueCached(); } diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/TwoSideMPSubsystem/commands/RunProfileTwoSides.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/TwoSideMPSubsystem/commands/RunProfileTwoSides.java index caf467f5..ebf6ef79 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/TwoSideMPSubsystem/commands/RunProfileTwoSides.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/TwoSideMPSubsystem/commands/RunProfileTwoSides.java @@ -15,7 +15,7 @@ * Loads and runs the given profiles into the given subsystem. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class RunProfileTwoSides extends YamlCommandGroupWrapper { +public class RunProfileTwoSides extends YamlCommandGroupWrapper { /** * Default constructor. diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunLoadedProfile.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunLoadedProfile.java index 78da9e65..4260a4ef 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunLoadedProfile.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunLoadedProfile.java @@ -15,7 +15,7 @@ * Runs the command that is currently loaded in the given subsystem. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class RunLoadedProfile extends YamlCommandWrapper { +public class RunLoadedProfile extends YamlCommandWrapper { /** * The amount of time this command is allowed to run for, in milliseconds. diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunProfile.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunProfile.java index aab22d5d..d8f1a914 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunProfile.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/motionProfile/commands/RunProfile.java @@ -14,7 +14,7 @@ * Loads and runs the given profile into the given subsystem. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class RunProfile extends YamlCommandGroupWrapper { +public class RunProfile extends YamlCommandGroupWrapper { /** * Default constructor. diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemAHRS.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemAHRS.java new file mode 100644 index 00000000..81bf87ba --- /dev/null +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemAHRS.java @@ -0,0 +1,65 @@ +package org.usfirst.frc.team449.robot.subsystem.interfaces.navX; + + +import com.fasterxml.jackson.annotation.JsonTypeInfo; +import com.kauailabs.navx.frc.AHRS; +import org.jetbrains.annotations.NotNull; + +/** + * A subsystem that has a navX on it. + */ +@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT) +public interface SubsystemAHRS { + + /** + * Get the robot's heading. + * + * @return robot heading, in degrees, on [-180, 180]. + */ + double getHeading(); + + /** + * Get the robot's cached heading. + * + * @return robot heading, in degrees, on [-180, 180]. + */ + double getHeadingCached(); + + /** + * Get the robot's angular velocity. + * + * @return Angular velocity in degrees/sec + */ + double getAngularVel(); + + /** + * Get the robot's cached angular velocity. + * + * @return Angular velocity in degrees/sec + */ + double getAngularVelCached(); + + /** + * Get the robot's angular displacement since being turned on. + * + * @return Angular displacement in degrees. + */ + double getAngularDisplacement(); + + /** + * Get the robot's cached angular displacement since being turned on. + * + * @return Angular displacement in degrees. + */ + double getAngularDisplacementCached(); + + /** + * @return true if the gyroscope is currently overriden, false otherwise. + */ + boolean getOverrideGyro(); + + /** + * @param override true to override the gyro, false to un-override it. + */ + void setOverrideGyro(boolean override); +} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemNavX.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemNavX.java deleted file mode 100644 index d10ba487..00000000 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/SubsystemNavX.java +++ /dev/null @@ -1,36 +0,0 @@ -package org.usfirst.frc.team449.robot.subsystem.interfaces.navX; - - -import com.fasterxml.jackson.annotation.JsonTypeInfo; -import com.kauailabs.navx.frc.AHRS; -import org.jetbrains.annotations.NotNull; - -/** - * A subsystem that has a navX on it. - */ -@JsonTypeInfo(use = JsonTypeInfo.Id.CLASS, include = JsonTypeInfo.As.WRAPPER_OBJECT) -public interface SubsystemNavX { - - /** - * Get the robot's heading using the navX - * - * @return robot heading, in degrees, on [-180, 180] - */ - double getGyroOutput(); - - /** - * @return true if the navX is currently overriden, false otherwise. - */ - boolean getOverrideNavX(); - - /** - * @param override true to override the navX, false to un-override it. - */ - void setOverrideNavX(boolean override); - - /** - * @return An AHRS object representing this subsystem's navX. - */ - @NotNull - AHRS getNavX(); -} diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/OverrideNavX.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/OverrideNavX.java index 02652b83..9e53608d 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/OverrideNavX.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/OverrideNavX.java @@ -7,7 +7,7 @@ import org.jetbrains.annotations.NotNull; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandWrapper; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * Set whether or not to override the navX. @@ -24,7 +24,7 @@ public class OverrideNavX extends YamlCommandWrapper { * The subsystem to execute this command on. */ @NotNull - private final SubsystemNavX subsystem; + private final SubsystemAHRS subsystem; /** * Default constructor. @@ -33,7 +33,7 @@ public class OverrideNavX extends YamlCommandWrapper { * @param override Whether or not to override the navX. */ @JsonCreator - public OverrideNavX(@NotNull @JsonProperty(required = true) SubsystemNavX subsystem, + public OverrideNavX(@NotNull @JsonProperty(required = true) SubsystemAHRS subsystem, @JsonProperty(required = true) boolean override) { this.override = override; this.subsystem = subsystem; @@ -52,7 +52,7 @@ protected void initialize() { */ @Override protected void execute() { - subsystem.setOverrideNavX(override); + subsystem.setOverrideGyro(override); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/PIDAngleCommand.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/PIDAngleCommand.java index 21ce8650..5903d80f 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/PIDAngleCommand.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/PIDAngleCommand.java @@ -9,7 +9,7 @@ import org.jetbrains.annotations.NotNull; import org.jetbrains.annotations.Nullable; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommand; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * A command that uses a navX to turn to a certain angle. @@ -21,7 +21,7 @@ public abstract class PIDAngleCommand extends PIDCommand implements YamlCommand * The subsystem to execute this command on. */ @NotNull - protected final SubsystemNavX subsystem; + protected final SubsystemAHRS subsystem; /** * The minimum the robot should be able to output, to overcome friction. @@ -61,8 +61,8 @@ public PIDAngleCommand(@JsonProperty(required = true) double absoluteTolerance, double minimumOutput, @Nullable Double maximumOutput, double deadband, boolean inverted, - @NotNull @JsonProperty(required = true) SubsystemNavX subsystem, - @JsonProperty(required = true) double kP, + @NotNull @JsonProperty(required = true) SubsystemAHRS subsystem, + double kP, double kI, double kD) { //Set P, I and D. I and D will normally be 0 if you're using cascading control, like you should be. @@ -125,7 +125,7 @@ protected double processPIDOutput(double output) { * @param output The output from the WPILib angular PID loop. * @return That output after being deadbanded with the map-given deadband. */ - protected double deadbandOutput(double output){ + protected double deadbandOutput(double output) { return this.getPIDController().getError() > deadband ? output : 0; } @@ -139,7 +139,7 @@ protected double deadbandOutput(double output){ */ @Override protected double returnPIDInput() { - return subsystem.getGyroOutput(); + return subsystem.getHeadingCached(); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/ToggleOverrideNavX.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/ToggleOverrideNavX.java index 160cb1db..e7e17b9e 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/ToggleOverrideNavX.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/navX/commands/ToggleOverrideNavX.java @@ -7,7 +7,7 @@ import org.jetbrains.annotations.NotNull; import org.usfirst.frc.team449.robot.jacksonWrappers.YamlCommandWrapper; import org.usfirst.frc.team449.robot.other.Logger; -import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX; +import org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS; /** * Toggle whether or not to override the navX. @@ -19,7 +19,7 @@ public class ToggleOverrideNavX extends YamlCommandWrapper { * The subsystem to execute this command on. */ @NotNull - private final SubsystemNavX subsystem; + private final SubsystemAHRS subsystem; /** * Default constructor. @@ -27,7 +27,7 @@ public class ToggleOverrideNavX extends YamlCommandWrapper { * @param subsystem The subsystem to execute this command on */ @JsonCreator - public ToggleOverrideNavX(@NotNull @JsonProperty(required = true) SubsystemNavX subsystem) { + public ToggleOverrideNavX(@NotNull @JsonProperty(required = true) SubsystemAHRS subsystem) { this.subsystem = subsystem; } @@ -44,7 +44,7 @@ protected void initialize() { */ @Override protected void execute() { - subsystem.setOverrideNavX(!subsystem.getOverrideNavX()); + subsystem.setOverrideGyro(!subsystem.getOverrideGyro()); } /** diff --git a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/shooter/commands/TurnAllOffWithRequires.java b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/shooter/commands/TurnAllOffWithRequires.java index bc13ed93..ed60936d 100644 --- a/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/shooter/commands/TurnAllOffWithRequires.java +++ b/RoboRIO/src/main/java/org/usfirst/frc/team449/robot/subsystem/interfaces/shooter/commands/TurnAllOffWithRequires.java @@ -13,7 +13,7 @@ * continue running. */ @JsonIdentityInfo(generator = ObjectIdGenerators.StringIdGenerator.class) -public class TurnAllOffWithRequires extends TurnAllOff { +public class TurnAllOffWithRequires extends TurnAllOff { /** * Default constructor diff --git a/RoboRIO/src/main/resources/100InchProfile.csv b/RoboRIO/src/main/resources/100InchProfile.csv deleted file mode 100644 index 7e14e450..00000000 --- a/RoboRIO/src/main/resources/100InchProfile.csv +++ /dev/null @@ -1,101 +0,0 @@ -100 -3.725577680424854E-4, 0.014902310721699414, 0.05, -0.0018627888402124272, 0.029804621443398835, 0.05, -0.005215808752594787, 0.06706039824764719, 0.05, -0.011176733041274537, 0.11921848577359499, 0.05, -0.020490677242336646, 0.18627888402124218, 0.05, -0.03353019912382364, 0.26079043762973997, 0.05, -0.05029529868573616, 0.3353019912382503, 0.05, -0.07078597592807367, 0.4098135448467505, 0.05, -0.09500223085083623, 0.48432509845525107, 0.05, -0.12294406345402376, 0.5588366520637505, 0.05, -0.15461147373763628, 0.6333482056722506, 0.05, -0.19000446170167384, 0.7078597592807512, 0.05, -0.22912302734613643, 0.7823713128892518, 0.05, -0.27196717067102, 0.8568828664976713, 0.05, -0.3185368916763163, 0.9313944201059265, 0.05, -0.36883219036203646, 1.0059059737144027, 0.05, -0.42285306672818035, 1.0804175273228778, 0.05, -0.4805995207747478, 1.1549290809313495, 0.05, -0.5420715525017539, 1.229440634540121, 0.05, -0.6072691619092141, 1.3039521881492044, 0.05, -0.6761923489971006, 1.3784637417577295, 0.05, -0.7488411137654133, 1.4529752953662545, 0.05, -0.8252154562141524, 1.5274868489747817, 0.05, -0.9053153763433178, 1.601998402583309, 0.05, -0.9891408741529095, 1.676509956191834, 0.05, -1.0766919496428788, 1.7510215097993886, 0.05, -1.1679686028131964, 1.8255330634063505, 0.05, -1.2629708336639351, 1.9000446170147756, 0.05, -1.361698642195095, 1.9745561706231962, 0.05, -1.4641520284066762, 2.0490677242316258, 0.05, -1.570330992298678, 2.123579277840033, 0.05, -1.6802355338711015, 2.1980908314484715, 0.05, -1.7938656531239459, 2.2726023850568877, 0.05, -1.9112213500572113, 2.3471139386653084, 0.05, -2.0323026246708977, 2.4216254922737335, 0.05, -2.157109476965006, 2.496137045882163, 0.05, -2.2856419069395346, 2.570648599490575, 0.05, -2.4178999145944844, 2.6451601530989954, 0.05, -2.5538834999298556, 2.719671706707425, 0.05, -2.693592662945648, 2.7941832603158456, 0.05, -2.8370274036418612, 2.8686948139242663, 0.05, -2.9841877220184956, 2.943206367532687, 0.05, -3.135073618075551, 3.0177179211411076, 0.05, -3.289685091813028, 3.092229474749537, 0.05, -3.448022143230926, 3.1667410283579667, 0.05, -3.609712214561203, 3.233801426605538, 0.05, -3.774010190267775, 3.285959514131438, 0.05, -3.9401709548145574, 3.3232152909356483, 0.05, -4.107449392665465, 3.345568757018169, 0.05, -4.274991203586561, 3.350836218421911, 0.05, -4.441942087343029, 3.3390176751293588, 0.05, -4.60755692839845, 3.312296821108429, 0.05, -4.7710906112167395, 3.2706736563657834, 0.05, -4.9317980202618035, 3.2141481809012795, 0.05, -5.089043224696016, 3.144904088684246, 0.05, -5.242562851449786, 3.070392535075399, 0.05, -5.392356900523113, 2.995880981466552, 0.05, -5.5384253719159995, 2.921369427857723, 0.05, -5.680768265628443, 2.846857874248876, 0.05, -5.819385581660446, 2.7723463206400467, 0.05, -5.954277320012006, 2.6978347670311997, 0.05, -6.085443480683124, 2.6233232134223705, 0.05, -6.212884063673801, 2.5488116598135413, 0.05, -6.336599068984037, 2.474300106204712, 0.05, -6.45658849661383, 2.399788552595865, 0.05, -6.572852346563181, 2.325276998987018, 0.05, -6.685390618832091, 2.2507654453782067, 0.05, -6.794203313420559, 2.1762538917693597, 0.05, -6.899290430328586, 2.1017423381605305, 0.05, -7.00065196955617, 2.0272307845516835, 0.05, -7.098287931103313, 1.9527192309428543, 0.05, -7.192198314970013, 1.8782076773340073, 0.05, -7.282383121156271, 1.8036961237251603, 0.05, -7.368842349662089, 1.7291845701163666, 0.05, -7.451576000487464, 1.654673016507484, 0.05, -7.530584073632397, 1.5801614628986727, 0.05, -7.605866569096889, 1.5056499092898434, 0.05, -7.677423486880939, 1.4311383556809965, 0.05, -7.745254826984548, 1.3566268020721672, 0.05, -7.809360589407713, 1.2821152484633025, 0.05, -7.869740774150436, 1.2076036948544733, 0.05, -7.9263953812127195, 1.1330921412456618, 0.05, -7.97932441059456, 1.0585805876368148, 0.05, -8.028527862295961, 0.9840690340280212, 0.05, -8.074005736316918, 0.9095574804191386, 0.05, -8.115758032657434, 0.8350459268103094, 0.05, -8.153784751317506, 0.7605343732014447, 0.05, -8.18808589229714, 0.6860228195926865, 0.05, -8.21866145559633, 0.6115112659837862, 0.05, -8.245511441215076, 0.5369997123749215, 0.05, -8.268635849153382, 0.4624881587661278, 0.05, -8.288034679411247, 0.3879766051572986, 0.05, -8.303707931988669, 0.31346505154843385, 0.05, -8.31565560688565, 0.23895349793964016, 0.05, -8.323986888800647, 0.1666256382999265, 0.05, -8.329183520200157, 0.1039326279902042, 0.05, -8.331990616620272, 0.056141928402304586, 0.05, -8.33315329359708, 0.02325353953615661, 0.05, -8.333416666666666, 0.005267461391724737, 0.05, -8.333416666666666, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/200InchProfile.csv b/RoboRIO/src/main/resources/200InchProfile.csv deleted file mode 100644 index 4d65afca..00000000 --- a/RoboRIO/src/main/resources/200InchProfile.csv +++ /dev/null @@ -1,141 +0,0 @@ -140 -3.7046456709843053E-4, 0.01481858268393722, 0.05, -0.0018523228354921527, 0.029637165367874443, 0.05, -0.0051865039393780244, 0.06668362207771744, 0.05, -0.011113937012952897, 0.11854866147149745, 0.05, -0.020375551190413635, 0.18523228354921475, 0.05, -0.03334181103885868, 0.2593251969689008, 0.05, -0.05001271655828801, 0.33341811038858665, 0.05, -0.07038826774870185, 0.407511023808277, 0.05, -0.09446846461010082, 0.4816039372279793, 0.05, -0.12225330714248424, 0.5556968506476684, 0.05, -0.15374279534585217, 0.6297897640673583, 0.05, -0.18893692922020444, 0.7038826774870455, 0.05, -0.22783570876554127, 0.7779755909067365, 0.05, -0.2704391339818625, 0.8520685043264237, 0.05, -0.3167472048691682, 0.9261614177461142, 0.05, -0.36675992142745834, 1.000254331165803, 0.05, -0.4204772836567329, 1.0743472445854918, 0.05, -0.477899291556992, 1.1484401580051817, 0.05, -0.5390259451282293, 1.222533071424745, 0.05, -0.6038572443704348, 1.2966259848441086, 0.05, -0.6723931892836236, 1.3707188982637764, 0.05, -0.7446337798677954, 1.4448118116834374, 0.05, -0.8205790161229504, 1.5189047251030985, 0.05, -0.9002288980490885, 1.5929976385227618, 0.05, -0.9835834256462098, 1.6670905519424273, 0.05, -1.0706425989143344, 1.7411834653624902, 0.05, -1.1614064178534853, 1.8152763787830173, 0.05, -1.2558748824636217, 1.8893692922027272, 0.05, -1.3540479927447437, 1.9634622056224416, 0.05, -1.4559257486968515, 2.037555119042156, 0.05, -1.5615081503199453, 2.1116480324618747, 0.05, -1.6707951976140245, 2.1857409458815846, 0.05, -1.7837868905790895, 2.259833859301299, 0.05, -1.9004832292151403, 2.333926772721018, 0.05, -2.020884213522177, 2.408019686140732, 0.05, -2.144989843500114, 2.482112599558741, 0.05, -2.2728001191489446, 2.5562055129766126, 0.05, -2.4043150404687554, 2.630298426396216, 0.05, -2.5395346074595473, 2.704391339815837, 0.05, -2.67845882012132, 2.778484253235458, 0.05, -2.8210876784540733, 2.8525771666550614, 0.05, -2.967421182457807, 2.9266700800746737, 0.05, -3.1174593321325217, 3.0007629934942948, 0.05, -3.271202127478216, 3.074855906913889, 0.05, -3.428649568494892, 3.148948820333519, 0.05, -3.589801655182548, 3.2230417337531136, 0.05, -3.7546583875411845, 3.2971346471727347, 0.05, -3.923219765570802, 3.371227560592347, 0.05, -4.095485789271399, 3.4453204740119503, 0.05, -4.271456458642979, 3.519413387431598, 0.05, -4.451131773685538, 3.5935063008511747, 0.05, -4.634511734399077, 3.667599214270787, 0.05, -4.821596340783598, 3.741692127690417, 0.05, -5.012385592839098, 3.8157850411099936, 0.05, -5.206879490565581, 3.889877954529659, 0.05, -5.405078033963042, 3.963970867949218, 0.05, -5.606981223031484, 4.038063781368848, 0.05, -5.812589057770908, 4.112156694788478, 0.05, -6.021901538181312, 4.1862496082080725, 0.05, -6.234918664262696, 4.260342521627685, 0.05, -6.451640436015061, 4.334435435047297, 0.05, -6.672066853438406, 4.408528348466909, 0.05, -6.896197916532733, 4.482621261886539, 0.05, -7.12403362529804, 4.5567141753061335, 0.05, -7.355573979734327, 4.630807088725746, 0.05, -7.590448515274498, 4.697490710803418, 0.05, -7.827916302784354, 4.749355750197122, 0.05, -8.0672364131297, 4.786402206906928, 0.05, -8.307667917176342, 4.808630080932836, 0.05, -8.548178648145617, 4.810214619385498, 0.05, -8.787736439256616, 4.79115582221997, 0.05, -9.025600361374998, 4.7572784423676495, 0.05, -9.261029485366567, 4.708582479831378, 0.05, -9.493282882097112, 4.645067934610907, 0.05, -9.7219108600781, 4.572559559619762, 0.05, -9.946834192388087, 4.498466646199724, 0.05, -10.168052879027073, 4.424373732779721, 0.05, -10.385566919995057, 4.350280819359682, 0.05, -10.59937631529204, 4.276187905939679, 0.05, -10.809481064918021, 4.202094992519605, 0.05, -11.015881168873003, 4.1280020790996375, 0.05, -11.218576627156981, 4.053909165679563, 0.05, -11.417567439769957, 3.979816252259525, 0.05, -11.612853606711935, 3.9057233388395574, 0.05, -11.80443512798291, 3.8316304254194833, 0.05, -11.992312003582885, 3.757537511999516, 0.05, -12.176484233511859, 3.6834445985794773, 0.05, -12.356951817769831, 3.6093516851594387, 0.05, -12.533714756356803, 3.5352587717394357, 0.05, -12.706773049272773, 3.461165858319397, 0.05, -12.876126696517742, 3.387072944899394, 0.05, -13.041775698091708, 3.31298003147932, 0.05, -13.203720053994676, 3.2388871180593526, 0.05, -13.36195976422664, 3.1647942046392785, 0.05, -13.516494828787602, 3.09070129121924, 0.05, -13.667325247677566, 3.0166083777992725, 0.05, -13.814451020896529, 2.9425154643792695, 0.05, -13.957872148444489, 2.8684225509591954, 0.05, -14.097588630321447, 2.794329637539157, 0.05, -14.233600466527408, 2.720236724119225, 0.05, -14.365907657062364, 2.6461438106991153, 0.05, -14.494510201926321, 2.572050897279148, 0.05, -14.619408101119276, 2.4979579838591093, 0.05, -14.74060135464123, 2.4238650704390707, 0.05, -14.858089962492183, 2.3497721570190677, 0.05, -14.971873924672133, 2.2756792435989937, 0.05, -15.08195324118108, 2.201586330178955, 0.05, -15.18832791201903, 2.1274934167589876, 0.05, -15.290997937185978, 2.053400503338949, 0.05, -15.389963316681925, 1.979307589918946, 0.05, -15.48522405050687, 1.9052146764989075, 0.05, -15.576780138660814, 1.831121763078869, 0.05, -15.664631581143757, 1.757028849658866, 0.05, -15.748778377955698, 1.6829359362388274, 0.05, -15.829220529096641, 1.60884302281886, 0.05, -15.905958034566583, 1.5347501093988214, 0.05, -15.978990894365522, 1.4606571959787829, 0.05, -16.04831910849346, 1.3865642825587088, 0.05, -16.113942676950394, 1.3124713691387058, 0.05, -16.175861599736333, 1.2383784557187738, 0.05, -16.234075876851264, 1.1642855422986287, 0.05, -16.2885855082952, 1.0901926288786967, 0.05, -16.33939049406813, 1.0160997154586227, 0.05, -16.386490834170058, 0.9420068020385486, 0.05, -16.42988652860099, 0.8679138886186166, 0.05, -16.469577577360916, 0.7938209751985426, 0.05, -16.505563980449843, 0.7197280617785395, 0.05, -16.537845737867766, 0.6456351483584655, 0.05, -16.566422849614693, 0.5715422349385335, 0.05, -16.591295315690612, 0.4974493215183884, 0.05, -16.612463136095535, 0.4233564080984564, 0.05, -16.629926310829457, 0.3492634946784534, 0.05, -16.64368483989238, 0.2751705812584504, 0.05, -16.653738723284295, 0.20107766783830527, 0.05, -16.660379198650872, 0.13280950733154384, 0.05, -16.664267968204864, 0.07777539107983955, 0.05, -16.66614596108047, 0.03755985751212165, 0.05, -16.666754106411897, 0.012162906628532255, 0.05, -16.666833333333336, 0.0015845384287871411, 0.05, -16.666833333333336, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/50InchProfile.csv b/RoboRIO/src/main/resources/50InchProfile.csv deleted file mode 100644 index 329a176a..00000000 --- a/RoboRIO/src/main/resources/50InchProfile.csv +++ /dev/null @@ -1,73 +0,0 @@ -72 -3.741183637055556E-4, 0.014964734548222221, 0.05, -0.0018705918185277757, 0.0299294690964444, 0.05, -0.005237657091877767, 0.06734130546699983, 0.05, -0.011223550911166641, 0.11971787638577748, 0.05, -0.020576510003805695, 0.18705918185278106, 0.05, -0.03367065273350067, 0.2618828545938995, 0.05, -0.05050597910025136, 0.33670652733501377, 0.05, -0.07108248910405773, 0.41153020007612756, 0.05, -0.09540018274491985, 0.4863538728172423, 0.05, -0.12345906002283766, 0.5611775455583562, 0.05, -0.15525912093780248, 0.6360012182992963, 0.05, -0.19080036548981935, 0.7108248910403375, 0.05, -0.2300827936788907, 0.785648563781427, 0.05, -0.2731064055050252, 0.8604722365226897, 0.05, -0.31987120096823773, 0.935295909264251, 0.05, -0.37037718006850734, 1.010119582005392, 0.05, -0.424624342805834, 1.0849432547465332, 0.05, -0.4826126891802176, 1.159766927487672, 0.05, -0.5443422191916254, 1.234590600228157, 0.05, -0.6098129328400322, 1.3094142729681368, 0.05, -0.6790248301254906, 1.384237945709168, 0.05, -0.751977911048001, 1.459061618450208, 0.05, -0.8286721756075633, 1.533885291191246, 0.05, -0.9091076238041774, 1.6087089639322816, 0.05, -0.9932842556378432, 1.683532636673315, 0.05, -1.0812020711085606, 1.7583563094143506, 0.05, -1.17286107021633, 1.8331799821553885, 0.05, -1.2682612529611514, 1.9080036548964285, 0.05, -1.3674026193430244, 1.9828273276374597, 0.05, -1.4702851693619494, 2.0576510003785, 0.05, -1.5769089030179262, 2.1324746731195354, 0.05, -1.6868997019472494, 2.1998159785864635, 0.05, -1.7995093294225089, 2.2521925495051898, 0.05, -1.9139895487162946, 2.2896043858757142, 0.05, -2.029592123101196, 2.3120514876980236, 0.05, -2.145541549380378, 2.318988525583645, 0.05, -2.261062324356611, 2.3104154995246518, 0.05, -2.3754062113021814, 2.2868777389114125, 0.05, -2.4878249734896762, 2.248375243749896, 0.05, -2.597570374191681, 2.1949080140400934, 0.05, -2.7039214431505494, 2.1270213791773696, 0.05, -2.8065313284723463, 2.0521977064359387, 0.05, -2.9054000301570695, 1.9773740336944634, 0.05, -3.0005275482047207, 1.9025503609530237, 0.05, -3.091913882615299, 1.8277266882115661, 0.05, -3.1795590333888053, 1.7529030154701264, 0.05, -3.2634630005252383, 1.67807934272866, 0.05, -3.3436257840245993, 1.6032556699872202, 0.05, -3.420047383886888, 1.5284319972457716, 0.05, -3.4927278001121036, 1.453608324504314, 0.05, -3.561667032700246, 1.3787846517628477, 0.05, -3.626865081651317, 1.3039609790214168, 0.05, -3.6883219469653143, 1.2291373062799504, 0.05, -3.7460376286422394, 1.1543136335385018, 0.05, -3.800012126682093, 1.079489960797071, 0.05, -3.8502454410848728, 1.0046662880555957, 0.05, -3.89673757185058, 0.929842615314147, 0.05, -3.9394885189792155, 0.8550189425727073, 0.05, -3.978498282470777, 0.780195269831232, 0.05, -4.013766862325268, 0.7053715970898189, 0.05, -4.045294258542685, 0.6305479243483525, 0.05, -4.0730804711230295, 0.5557242516068861, 0.05, -4.097125500066301, 0.48090057886543747, 0.05, -4.117429345372501, 0.40607690612398883, 0.05, -4.133992007041627, 0.33125323338252244, 0.05, -4.1468134850736815, 0.25642956064109157, 0.05, -4.155921045938434, 0.18215121729504347, 0.05, -4.161716074469361, 0.11590057061853898, 0.05, -4.164946807393877, 0.06461465849032066, 0.05, -4.166361481439395, 0.02829348091037076, 0.05, -4.1667083333333315, 0.006937037878724794, 0.05, -4.1667083333333315, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftBackupBlueProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftBackupBlueProfile.csv deleted file mode 100644 index 5e568888..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftBackupBlueProfile.csv +++ /dev/null @@ -1,81 +0,0 @@ -80 -3.6982739809204466E-4, 0.014793095923681785, 0.05, -4.985759113922851E-4, 0.002574970266004809, 0.05, -7.7656203092718E-4, 0.005559722390697899, 0.05, -0.0012305229107268314, 0.009079217595993026, 0.05, -0.0018356548305975184, 0.012102638397413741, 0.05, -0.0024660442933936754, 0.012607789255923135, 0.05, -0.0028969787598687726, 0.008618689329501949, 0.05, -0.0029656327398297462, 0.0013730795992194689, 0.05, -0.003917457624949561, 0.019036497702396293, 0.05, -0.00622850161017923, 0.04622087970459338, 0.05, -0.010475906973102543, 0.08494810725846627, 0.05, -0.01734369682808689, 0.13735579709968695, 0.05, -0.027621109862164803, 0.20554826068155826, 0.05, -0.04218566148910695, 0.2912910325388428, 0.05, -0.061958604321971616, 0.39545885665729336, 0.05, -0.08781550888374035, 0.5171380912353744, 0.05, -0.12043237606711718, 0.6523373436675365, 0.05, -0.16005518306585603, 0.792456139974777, 0.05, -0.20620904006659124, 0.9230771400147044, 0.05, -0.2574187592640952, 1.0241943839500782, 0.05, -0.31107682858123303, 1.0731613863427567, 0.05, -0.3636067272694322, 1.0505979737639835, 0.05, -0.410963363430608, 0.9471327232235157, 0.05, -0.44931788275167384, 0.7670903864213159, 0.05, -0.4756478503176118, 0.5265993513187593, 0.05, -0.48802058730877906, 0.24745473982334495, 0.05, -0.4904941048804369, 0.04947035143315641, 0.05, -0.5078990063096007, 0.34809802858327693, 0.05, -0.5398241518943961, 0.638502911695909, 0.05, -0.585616240946811, 0.9158417810482969, 0.05, -0.6445676367285607, 1.179027915634994, 0.05, -0.7160372147036138, 1.4293915595010627, 0.05, -0.7995247553481823, 1.6697508128913718, 0.05, -0.894719276783317, 1.9038904287026919, 0.05, -1.0015383218269927, 2.1363809008735113, 0.05, -1.119805536488683, 2.3653442932338082, 0.05, -1.2491842942500533, 2.587575155227406, 0.05, -1.389538999342875, 2.807094101856437, 0.05, -1.5410063165047614, 3.029346343237728, 0.05, -1.7038347715948368, 3.256569101801506, 0.05, -1.8786105709393497, 3.495515986890257, 0.05, -2.066539998344398, 3.7585885481009615, 0.05, -2.2691905222331012, 4.053010477774067, 0.05, -2.48823782951239, 4.380946145585778, 0.05, -2.7252137301945587, 4.739518013643371, 0.05, -2.980990510334077, 5.115535602790368, 0.05, -3.2541318551564924, 5.462826896448307, 0.05, -3.539085198793581, 5.699066872741776, 0.05, -3.8261681061906088, 5.74165814794055, 0.05, -4.1040524093362905, 5.55768606291364, 0.05, -4.3634676893429996, 5.188305600134175, 0.05, -4.599426475228326, 4.71917571770653, 0.05, -4.81097781122265, 4.231026719886482, 0.05, -4.999670863102945, 3.7738610376058865, 0.05, -5.16808918987127, 3.368366535366512, 0.05, -5.318953201800508, 3.0172802385847755, 0.05, -5.454712646235337, 2.7151888886965803, 0.05, -5.577422747246623, 2.454202020225726, 0.05, -5.688750480711567, 2.2265546692988893, 0.05, -5.7900276647536835, 2.0255436808423335, 0.05, -5.882312983262631, 1.8457063701789578, 0.05, -5.9664483526698096, 1.682707388143575, 0.05, -6.043105527091024, 1.5331434884242803, 0.05, -6.112822992779664, 1.3943493137727994, 0.05, -6.176034589058771, 1.2642319255821435, 0.05, -6.233091508764189, 1.1411383941083546, 0.05, -6.284279168238342, 1.023753189483056, 0.05, -6.329830146768663, 0.9110195706064304, 0.05, -6.369934138415858, 0.8020798329438907, 0.05, -6.404745613871828, 0.6962295091193935, 0.05, -6.434389735445252, 0.5928824314684692, 0.05, -6.458966911088362, 0.4915435128622201, 0.05, -6.47855628914785, 0.3917875611897482, 0.05, -6.493218402451052, 0.29324226606404385, 0.05, -6.503230922396879, 0.2002503989165522, 0.05, -6.509338978135295, 0.12216111476832148, 0.05, -6.51252358655404, 0.0636921683748957, 0.05, -6.51375686965639, 0.02466566204701241, 0.05, -6.514006819848782, 0.004999003847829636, 0.05, -6.514006819848782, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftBackupRedProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftBackupRedProfile.csv deleted file mode 100644 index 37f7fc7f..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftBackupRedProfile.csv +++ /dev/null @@ -1,77 +0,0 @@ -76 -3.6656246461197776E-4, 0.01466249858447911, 0.05, -9.791665548139147E-4, 0.012252081804038738, 0.05, -0.0023531440773313568, 0.02747955045034884, 0.05, -0.004780744239436568, 0.04855200324210423, 0.05, -0.008535158246977557, 0.07508828015081978, 0.05, -0.01371139135841723, 0.10352466222879342, 0.05, -0.020228009512528858, 0.13033236308223256, 0.05, -0.027978237114347847, 0.1550045520363798, 0.05, -0.036828508887296676, 0.17700543545897654, 0.05, -0.04661686028708562, 0.19576702799577891, 0.05, -0.05715131926310739, 0.21068917952043525, 0.05, -0.06820856186911495, 0.2211448521201511, 0.05, -0.07953324640687294, 0.2264936907551598, 0.05, -0.0908386601354426, 0.22610827457139315, 0.05, -0.10180961566128952, 0.21941911051693813, 0.05, -0.11210893004836657, 0.20598628774154099, 0.05, -0.12138928641382929, 0.18560712730925427, 0.05, -0.12931273541729696, 0.1584689800693534, 0.05, -0.13558034752228473, 0.12535224209975532, 0.05, -0.13997420969770125, 0.08787724350833037, 0.05, -0.14241250995961127, 0.04876600523820032, 0.05, -0.14301524016203418, 0.012054604048458128, 0.05, -0.14385794910562066, 0.01685417887172958, 0.05, -0.14542873677356916, 0.03141575335896977, 0.05, -0.14665787477233275, 0.024582759975272032, 0.05, -0.14716753909236602, 0.010193286400665205, 0.05, -0.15105476646526947, 0.07774454745806884, 0.05, -0.16006519069167005, 0.18020848452801166, 0.05, -0.1758937983702557, 0.3165721535717131, 0.05, -0.2000447176791903, 0.48301838617869214, 0.05, -0.23373917435026775, 0.6738891334215488, 0.05, -0.2778847310140333, 0.8829111332753117, 0.05, -0.33309946174521693, 1.104294614623672, 0.05, -0.39954671423691207, 1.3289450498339024, 0.05, -0.4768703610906148, 1.5464729370740544, 0.05, -0.5644362549359094, 1.7513178769058926, 0.05, -0.6614313210468661, 1.9399013222191324, 0.05, -0.7666941903277551, 2.1052573856177808, 0.05, -0.878942876420234, 2.244973721849579, 0.05, -0.9970857645456398, 2.3628577625081153, 0.05, -1.1200120710942167, 2.4585261309715403, 0.05, -1.2465744043232094, 2.531246664579852, 0.05, -1.3758892359140522, 2.586296631816856, 0.05, -1.5075041136355, 2.6322975544289573, 0.05, -1.6411090805540542, 2.672099338371081, 0.05, -1.776398510007321, 2.7057885890653326, 0.05, -1.9130381059142199, 2.732791918137977, 0.05, -2.050634883833412, 2.7519355583838436, 0.05, -2.1887122434803388, 2.7615471929385365, 0.05, -2.3266931732850304, 2.7596185960938358, 0.05, -2.4638949333144198, 2.744035200587783, 0.05, -2.599537839535931, 2.712858124430233, 0.05, -2.7327688533625323, 2.664620276532018, 0.05, -2.862697869695954, 2.598580326668441, 0.05, -2.988441713171257, 2.5148768695060557, 0.05, -3.109168963193292, 2.414545000440701, 0.05, -3.224138612728409, 2.2993929907023314, 0.05, -3.332727289029443, 2.171773526020676, 0.05, -3.434442631396106, 2.0343068473332604, 0.05, -3.5289233775568207, 1.8896149232143005, 0.05, -3.6159288728554855, 1.7401099059732938, 0.05, -3.695321710112841, 1.5878567451471082, 0.05, -3.767047139691447, 1.4345085915721274, 0.05, -3.831112171526468, 1.2813006367004205, 0.05, -3.8875663148788666, 1.1290828670479662, 0.05, -3.9364850047380906, 0.9783737971844795, 0.05, -3.977956062890647, 0.8294211630511292, 0.05, -4.012069098084599, 0.6822607038790504, 0.05, -4.038907503367771, 0.5367681056634268, 0.05, -4.058542623209151, 0.3927023968276111, 0.05, -4.071556739317168, 0.26028232216033054, 0.05, -4.0792205823408105, 0.1532768604728515, 0.05, -4.082968783214991, 0.07496401748359684, 0.05, -4.08422482369094, 0.02512080951899246, 0.05, -4.084407275101284, 0.0036490282068662, 0.05, -4.084407275101284, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftBlueShootProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftBlueShootProfile.csv deleted file mode 100644 index 81466a13..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftBlueShootProfile.csv +++ /dev/null @@ -1,89 +0,0 @@ -88 -3.6985651373580244E-4, 0.014794260549432097, 0.05, -0.0013907084347288814, 0.020417038419861578, 0.05, -0.0036876603537088397, 0.045939038379599166, 0.05, -0.007771257584488416, 0.08167194461559152, 0.05, -0.01415223712875711, 0.1276195908853739, 0.05, -0.023086446807644143, 0.1786841935777406, 0.05, -0.03457496991044085, 0.2297704620559342, 0.05, -0.04861955045821649, 0.2808916109555127, 0.05, -0.06522285808654618, 0.33206615256659394, 0.05, -0.08438881345959127, 0.3833191074609019, 0.05, -0.10612297374717461, 0.4346832057516668, 0.05, -0.13043297713543592, 0.4862000677652263, 0.05, -0.15732904473872225, 0.5379213520657266, 0.05, -0.18682453582320532, 0.5899098216896616, 0.05, -0.21893655071294268, 0.642240297794747, 0.05, -0.2536865726219351, 0.6950004381798484, 0.05, -0.2911011375192636, 0.7482912979465689, 0.05, -0.3312125164933481, 0.80222757948169, 0.05, -0.37405939306249314, 0.856937531382901, 0.05, -0.4196875129698048, 0.9125623981462331, 0.05, -0.46815028215812093, 0.9692553837663228, 0.05, -0.5195092855130401, 1.027180067098383, 0.05, -0.5738346982005946, 1.0865082537510913, 0.05, -0.6312055620508179, 1.1474172770044648, 0.05, -0.6917099016463794, 1.2100867919112288, 0.05, -0.7554446599583635, 1.2746951662396844, 0.05, -0.8225154402146823, 1.3414156051263755, 0.05, -0.893036050199829, 1.4104121997029355, 0.05, -0.9671278561200305, 1.481836118404029, 0.05, -1.0449189652227822, 1.5558221820550326, 0.05, -1.1265432684131835, 1.6324860638080292, 0.05, -1.2121393851467264, 1.7119223346708552, 0.05, -1.3018495618158092, 1.794203533381658, 0.05, -1.395818580746708, 1.879380378617976, 0.05, -1.4941927393141554, 1.9674831713489487, 0.05, -1.59711895709084, 2.05852435553369, 0.05, -1.7047440638509643, 2.152502135202486, 0.05, -1.8172143129520655, 2.249404982022021, 0.05, -1.9346751541127793, 2.3492168232142774, 0.05, -2.0569417930834346, 2.4453327794131074, 0.05, -2.1834733031793077, 2.5306302019174636, 0.05, -2.313686102474609, 2.604255985906026, 0.05, -2.4469540371867065, 2.665358694241952, 0.05, -2.5824216991901827, 2.7093532400695253, 0.05, -2.7191820204508854, 2.7352064252140567, 0.05, -2.856471048764387, 2.745780566270038, 0.05, -2.9934878088553454, 2.7403352018191653, 0.05, -3.1293960050530822, 2.7181639239547395, 0.05, -3.263526502964586, 2.6826099582300746, 0.05, -3.3955681746260473, 2.6408334332292207, 0.05, -3.525385855670251, 2.596353620884072, 0.05, -3.652849544637846, 2.5492737793519007, 0.05, -3.7778337395379467, 2.499683898002008, 0.05, -3.9002168621704993, 2.4476624526510546, 0.05, -4.019880783875992, 2.3932784341098583, 0.05, -4.1367104591414865, 2.336593505309885, 0.05, -4.250593667670996, 2.277664170590199, 0.05, -4.361420861035125, 2.2165438672825704, 0.05, -4.469085106124423, 2.153284901785958, 0.05, -4.573482114788245, 2.087940173276442, 0.05, -4.674510346686611, 2.0205646379673152, 0.05, -4.77207117081949, 1.9512164826575735, 0.05, -4.8660690703472245, 1.8799579905547021, 0.05, -4.956411875088921, 1.8068560948339132, 0.05, -5.043011006544067, 1.7319826291029319, 0.05, -5.125781721383308, 1.6554142967848073, 0.05, -5.204643340969523, 1.5772323917242965, 0.05, -5.279519456492313, 1.4975223104558122, 0.05, -5.350338101610653, 1.416372902366807, 0.05, -5.417031886984773, 1.3338757074823993, 0.05, -5.479538093550007, 1.2501241313046676, 0.05, -5.537798723734927, 1.165212603698395, 0.05, -5.591760511998516, 1.0792357652717994, 0.05, -5.641374897839778, 0.992287716825246, 0.05, -5.686597965977849, 0.9044613627614112, 0.05, -5.727390359442538, 0.8158478692937835, 0.05, -5.7637171720798595, 0.7265362527464333, 0.05, -5.795547827300663, 0.6366131044160603, 0.05, -5.8228559500203065, 0.5461624543928828, 0.05, -5.845619238361014, 0.45526576681414355, 0.05, -5.863819341456127, 0.3640020619022564, 0.05, -5.877441748779071, 0.27244814645887755, 0.05, -5.886721677765864, 0.18559857973587904, 0.05, -5.89235827552007, 0.11273195508410344, 0.05, -5.895268165456332, 0.058197798725237206, 0.05, -5.89637017732082, 0.022040237289764255, 0.05, -5.8965841606966825, 0.0042796675172478045, 0.05, -5.8965841606966825, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftLeftProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftLeftProfile.csv deleted file mode 100644 index e999a37e..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftLeftProfile.csv +++ /dev/null @@ -1,115 +0,0 @@ -114 -3.699747832301106E-4, 0.014798991329204423, 0.05, -0.0019830486621782275, 0.03226147757896233, 0.05, -0.00561256446612118, 0.07259031607885905, 0.05, -0.01206537763374221, 0.1290562633524206, 0.05, -0.022148771751964048, 0.20166788236443675, 0.05, -0.03626731537854654, 0.28237087253164983, 0.05, -0.05442280539734679, 0.363109800376005, 0.05, -0.07661755948986848, 0.44389508185043375, 0.05, -0.10285442144721893, 0.5247372391470089, 0.05, -0.13313676774816535, 0.6056469260189282, 0.05, -0.16746851539735536, 0.6866349529837998, 0.05, -0.20585413086986076, 0.7677123094501084, 0.05, -0.24829864010844827, 0.8488901847717502, 0.05, -0.2948076395083604, 0.9301799879982428, 0.05, -0.3453873079903378, 1.011593369639547, 0.05, -0.4000444201089447, 1.0931422423721382, 0.05, -0.4587863597894252, 1.1748387936096107, 0.05, -0.5216211350218101, 1.256695504647698, 0.05, -0.5885573927551387, 1.3387251546665728, 0.05, -0.6596044347132066, 1.4209408391613565, 0.05, -0.7347722333201894, 1.5033559721396552, 0.05, -0.8140714472095575, 1.5859842777873616, 0.05, -0.897513437005618, 1.66883979592121, 0.05, -0.9851102800464964, 1.7519368608175678, 0.05, -1.07687478423111, 1.8352900836922736, 0.05, -1.172820500080309, 1.9189143169839813, 0.05, -1.2729617309997414, 2.002824618388651, 0.05, -1.3773135401110441, 2.0870361822260555, 0.05, -1.485891753974331, 2.171564277265737, 0.05, -1.598712961152709, 2.2564241435675547, 0.05, -1.7157945055206292, 2.341630887358407, 0.05, -1.8371544721015962, 2.4271993316193394, 0.05, -1.9628116644865874, 2.513143847699822, 0.05, -2.0927855724941584, 2.5994781601514214, 0.05, -2.2270963270323407, 2.6862150907636497, 0.05, -2.3657646415386044, 2.773366290125277, 0.05, -2.508811736183097, 2.8609418928898505, 0.05, -2.656259243468406, 2.9489501457061795, 0.05, -2.8081290915861348, 3.037396962354578, 0.05, -2.9644433628949614, 3.1262854261765276, 0.05, -3.1252241243012375, 3.2156152281255235, 0.05, -3.2904932263372326, 3.3053820407198997, 0.05, -3.460272067778295, 3.395576828821255, 0.05, -3.6345813227566177, 3.4861850995664536, 0.05, -3.8134406279501385, 3.5771861038704165, 0.05, -3.99686822741408, 3.6685519892788347, 0.05, -4.184880574672869, 3.760246945175772, 0.05, -4.377491891294759, 3.852226332437792, 0.05, -4.574713684531654, 3.944435864737892, 0.05, -4.776554227181546, 4.036810852997853, 0.05, -4.983018006258271, 4.129275581534487, 0.05, -5.1941051494581645, 4.221742863997881, 0.05, -5.409383382025361, 4.305564651343921, 0.05, -5.627984325678502, 4.3720188730628236, 0.05, -5.849029406428288, 4.420901614995726, 0.05, -6.071630866192358, 4.452029195281396, 0.05, -6.294593849364427, 4.459259663441382, 0.05, -6.516716550052375, 4.442454013758964, 0.05, -6.737092508266411, 4.4075191642807265, 0.05, -6.954814089393151, 4.354431622534818, 0.05, -7.1689746587239584, 4.283211386616145, 0.05, -7.3789704652794725, 4.199916131110283, 0.05, -7.584632553593756, 4.113241766285663, 0.05, -7.785927345530917, 4.025895838743214, 0.05, -7.9828261742573785, 3.937976574529242, 0.05, -8.175305169169198, 3.8495798982363683, 0.05, -8.363345072067093, 3.760798057957908, 0.05, -8.546930998104328, 3.6717185207447156, 0.05, -8.7260521532387, 3.58242310268744, 0.05, -8.900701521780165, 3.4929873708293178, 0.05, -9.070875533477986, 3.4034802339564294, 0.05, -9.236573722055075, 3.313963771541784, 0.05, -9.397798381957845, 3.2244931980553972, 0.05, -9.55455423208105, 3.1351170024641317, 0.05, -9.706848090253136, 3.0458771634416957, 0.05, -9.854688565240963, 2.9568094997565466, 0.05, -9.998085766501228, 2.867944025205317, 0.05, -10.13705103630862, 2.7793053961478367, 0.05, -10.271596703466564, 2.690913343158877, 0.05, -10.401735859985507, 2.6027831303788664, 0.05, -10.527482160492427, 2.514926010138405, 0.05, -10.648849642475199, 2.427349639655436, 0.05, -10.765852568131818, 2.340058513132367, 0.05, -10.878505285005943, 2.2530543374824945, 0.05, -10.986822104843476, 2.166336396750673, 0.05, -11.090817198974932, 2.079901882629116, 0.05, -11.190504508392266, 1.9937461883466756, 0.05, -11.285897667376052, 1.9078631796757284, 0.05, -11.377009939299416, 1.822245438467294, 0.05, -11.463854162783969, 1.7368844696910506, 0.05, -11.546442707305731, 1.6517708904352586, 0.05, -11.624787436931681, 1.5668945925190225, 0.05, -11.698899681020485, 1.4822448817760647, 0.05, -11.768790211214764, 1.3978106038855656, 0.05, -11.834469223135526, 1.313580238415235, 0.05, -11.895946323069426, 1.2295419986779865, 0.05, -11.95323051742171, 1.1456838870456787, 0.05, -12.006330206377726, 1.0619937791203153, 0.05, -12.055253178702724, 0.9784594464999724, 0.05, -12.10000660946163, 0.8950686151781025, 0.05, -12.140597058610428, 0.8118089829759458, 0.05, -12.177030471740828, 0.7286682626080022, 0.05, -12.209312180193628, 0.6456341690559899, 0.05, -12.237446903127259, 0.562694458672626, 0.05, -12.26143874919425, 0.4798369213398228, 0.05, -12.281291218572132, 0.39704938755764485, 0.05, -12.297007204808317, 0.31431972472367575, 0.05, -12.30858899673594, 0.23163583855248082, 0.05, -12.316326142507723, 0.1547429154356516, 0.05, -12.320920618251542, 0.09188951487635498, 0.05, -12.323199073937245, 0.04556911371406893, 0.05, -12.32398782918719, 0.015775104998935884, 0.05, -12.324113057994582, 0.002504576147826232, 0.05, -12.324113057994582, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftMidProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftMidProfile.csv deleted file mode 100644 index c1ba2db4..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftMidProfile.csv +++ /dev/null @@ -1,91 +0,0 @@ -90 -3.741923350751432E-4, 0.014967693403005728, 0.05, -0.0018709616753757154, 0.029935386806011443, 0.05, -0.005238692691051996, 0.0673546203135256, 0.05, -0.011225770052254273, 0.11974154722404554, 0.05, -0.02058057842913283, 0.1870961675375711, 0.05, -0.03367731015676313, 0.26193463455260596, 0.05, -0.05051596523514526, 0.33677310156764256, 0.05, -0.07109654366427896, 0.41161156858267406, 0.05, -0.09541904544416427, 0.4864500355977061, 0.05, -0.12348347057480115, 0.5612885026127375, 0.05, -0.15528981905618963, 0.6361269696277696, 0.05, -0.19083809088832968, 0.7109654366428009, 0.05, -0.23012828607121433, 0.785803903657693, 0.05, -0.2731604046048427, 0.8606423706725674, 0.05, -0.31993444648922126, 0.9354808376875712, 0.05, -0.37045041172435017, 1.0103193047025782, 0.05, -0.42470830031023254, 1.0851577717176475, 0.05, -0.48270811224690224, 1.159996238733394, 0.05, -0.5444498475343247, 1.2348347057484488, 0.05, -0.6099335061725002, 1.3096731727635103, 0.05, -0.6791590881614286, 1.3845116397785673, 0.05, -0.7521265935011098, 1.4593501067936243, 0.05, -0.828836022191544, 1.5341885738086836, 0.05, -0.9092873742326351, 1.6090270408218221, 0.05, -0.9934806496244581, 1.6838655078364617, 0.05, -1.081415848367029, 1.7587039748514188, 0.05, -1.1730929704603472, 1.8335424418663626, 0.05, -1.2685120159044134, 1.9083809088813242, 0.05, -1.367672984699227, 1.9832193758962724, 0.05, -1.4705758768447885, 2.0580578429112295, 0.05, -1.5772206923410976, 2.132896309926182, 0.05, -1.6876074311881546, 2.2077347769411393, 0.05, -1.8017360933859592, 2.282573243956092, 0.05, -1.9196066789345116, 2.357411710971049, 0.05, -2.041219187833812, 2.432250177986006, 0.05, -2.1665736200838595, 2.50708864500095, 0.05, -2.2956699756846546, 2.5819271120159026, 0.05, -2.428508254636198, 2.656765579030864, 0.05, -2.5650884569384886, 2.731604046045817, 0.05, -2.705410582591527, 2.8064425130607695, 0.05, -2.8491004392602384, 2.873797133374225, 0.05, -2.995409642274473, 2.9261840602846956, 0.05, -3.1435898069640813, 2.963603293792163, 0.05, -3.2928925486589145, 2.986054833896663, 0.05, -3.4425372456733605, 2.992893940288921, 0.05, -3.5917432763212798, 2.9841206129583853, 0.05, -3.7397622559321424, 2.9603795922172527, 0.05, -3.8858457998357925, 2.9216708780730016, 0.05, -4.029245523362077, 2.8679944705256943, 0.05, -4.169245278856756, 2.799995109893594, 0.05, -4.305503111000667, 2.725156642878215, 0.05, -4.43801901979381, 2.6503181758628536, 0.05, -4.566793005236184, 2.5754797088474746, 0.05, -4.691825067327788, 2.5006412418320956, 0.05, -4.813115206068626, 2.425802774816752, 0.05, -4.9306634214586955, 2.350964307801391, 0.05, -5.044469713497994, 2.2761258407859764, 0.05, -5.154534082186526, 2.201287373770633, 0.05, -5.26085652752429, 2.1264489067552717, 0.05, -5.363437049511284, 2.0516104397398927, 0.05, -5.462275648147509, 1.976771972724496, 0.05, -5.557372323432968, 1.901933505709188, 0.05, -5.648727075367657, 1.8270950386937734, 0.05, -5.736339903951578, 1.7522565716784122, 0.05, -5.82021080918473, 1.677418104663051, 0.05, -5.900339791067116, 1.6025796376477075, 0.05, -5.976726849598729, 1.5277411706322752, 0.05, -6.049371984779578, 1.4529027036169673, 0.05, -6.118275196609655, 1.3780642366015528, 0.05, -6.183436485088967, 1.303225769586227, 0.05, -6.244855850217507, 1.2283873025708125, 0.05, -6.302533291995281, 1.153548835555469, 0.05, -6.356468810422285, 1.07871036854009, 0.05, -6.406662405498523, 1.0038719015247466, 0.05, -6.453114077223989, 0.9290334345093321, 0.05, -6.495823825598689, 0.8541949674939886, 0.05, -6.534791650622619, 0.7793565004786096, 0.05, -6.570017552295782, 0.7045180334632661, 0.05, -6.601501530618175, 0.6296795664478516, 0.05, -6.629243585589801, 0.5548410994325259, 0.05, -6.653243717210658, 0.48000263241712915, 0.05, -6.673501925480747, 0.4051641654017857, 0.05, -6.6900182104000665, 0.3303256983863889, 0.05, -6.702792571968618, 0.2554872313710277, 0.05, -6.711857247202316, 0.1812935046739561, 0.05, -6.717618665452148, 0.11522836499665345, 0.05, -6.720825211388272, 0.06413091872246923, 0.05, -6.722225269680838, 0.028001165851314624, 0.05, -6.722567225, 0.006839106383242921, 0.05, -6.722567225, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftRedShootProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftRedShootProfile.csv deleted file mode 100644 index a1558f47..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftRedShootProfile.csv +++ /dev/null @@ -1,89 +0,0 @@ -88 -3.6985651373580244E-4, 0.014794260549432097, 0.05, -0.002295788883929778, 0.0385186474038795, 0.05, -0.006629102625072885, 0.08666627482286215, 0.05, -0.014332647052640902, 0.15407088855136034, 0.05, -0.026369083993339676, 0.2407287388139755, 0.05, -0.04321927530419736, 0.33700382621715363, 0.05, -0.06488216203229943, 0.4332577345620414, 0.05, -0.09135604095378316, 0.5294775784296746, 0.05, -0.12263830613342624, 0.6256453035928614, 0.05, -0.15872513247464237, 0.7217365268243227, 0.05, -0.19961110060664067, 0.817719362639966, 0.05, -0.24528876370449065, 0.9135532619569999, 0.05, -0.2957481591347731, 1.0091879086056483, 0.05, -0.35097626789113634, 1.1045621751272654, 0.05, -0.4109564279297768, 1.1996032007728097, 0.05, -0.4756677090241256, 1.2942256218869748, 0.05, -0.545084261341887, 1.388331046355229, 0.05, -0.6191746507966324, 1.4818077890949073, 0.05, -0.6979012004445359, 1.574530992958069, 0.05, -0.7812193578333003, 1.666363147775289, 0.05, -0.8690771134473141, 1.7571551122802758, 0.05, -0.9614144961065199, 1.8467476531841156, 0.05, -1.0581631728569874, 1.9349735350093478, 0.05, -1.1592461805246563, 2.021660153353378, 0.05, -1.2645778130309573, 2.106632650126021, 0.05, -1.3740636845591094, 2.189717430563043, 0.05, -1.4876009811558604, 2.270745931935017, 0.05, -1.605078904632179, 2.349558469526371, 0.05, -1.726379301715078, 2.4260079416579807, 0.05, -1.8513774597602475, 2.499963160903392, 0.05, -1.9799430385835632, 2.5713115764663166, 0.05, -2.111941097254136, 2.6399611734114594, 0.05, -2.2472331660093636, 2.7058413751045487, 0.05, -2.3856783076317574, 2.768902832447873, 0.05, -2.527134110473712, 2.829116056839097, 0.05, -2.6714575566743344, 2.8864689240124406, 0.05, -2.8185057142351315, 2.940963151215945, 0.05, -2.9681362095931645, 2.9926099071606553, 0.05, -3.1202074475965826, 3.0414247600683666, 0.05, -3.274169412283568, 3.0792392937397026, 0.05, -3.429088863091292, 3.098389016154485, 0.05, -3.5840740703014937, 3.0997041442040385, 0.05, -3.7382747356708586, 3.084013307387297, 0.05, -3.8906732846451293, 3.0479709794854153, 0.05, -4.040302428828478, 2.9925828836669774, 0.05, -4.186446005044041, 2.9228715243112515, 0.05, -4.328423899089462, 2.8395578809084356, 0.05, -4.46559039253736, 2.7433298689579404, 0.05, -4.59752749595813, 2.6387420684153993, 0.05, -4.724198624816487, 2.53342257716714, 0.05, -4.845735367860797, 2.4307348608862025, 0.05, -4.962264294232896, 2.3305785274419764, 0.05, -5.073907598047139, 2.2328660762848687, 0.05, -5.180783657709372, 2.1375211932446603, 0.05, -5.283007496644695, 2.0444767787064575, 0.05, -5.380691139176969, 1.953672850645496, 0.05, -5.473943860845942, 1.8650544333794694, 0.05, -5.56287233707043, 1.7785695244897433, 0.05, -5.647580697579269, 1.6941672101767693, 0.05, -5.72817049704464, 1.6117959893074123, 0.05, -5.804740614495881, 1.5314023490248152, 0.05, -5.8773870956466, 1.4529296230143807, 0.05, -5.946202953158657, 1.37631715024116, 0.05, -6.011277940034923, 1.3014997375253294, 0.05, -6.072698310869999, 1.228407416701512, 0.05, -6.130546584648731, 1.1569654755746486, 0.05, -6.184901321213857, 1.0870947313025319, 0.05, -6.235836921538312, 1.0187120064890978, 0.05, -6.283423459671967, 0.951730762673094, 0.05, -6.327726551840126, 0.8860618433631684, 0.05, -6.368807265752028, 0.8216142782380405, 0.05, -6.406722070870212, 0.7582961023636848, 0.05, -6.441522828332282, 0.696015149241395, 0.05, -6.473256817394176, 0.6346797812378758, 0.05, -6.501966793867464, 0.574199529465762, 0.05, -6.5276910749153245, 0.5144856209572164, 0.05, -6.550463643897702, 0.45545137964754107, 0.05, -6.570314268575001, 0.39701249354598295, 0.05, -6.587268625984424, 0.3390871481884689, 0.05, -6.601348427438267, 0.28159602907684556, 0.05, -6.612571537681542, 0.2244622048655063, 0.05, -6.620952082695239, 0.16761090027395112, 0.05, -6.6266515155914565, 0.11398865792435088, 0.05, -6.630109549196663, 0.06916067210412785, 0.05, -6.631893641153261, 0.03568183913195024, 0.05, -6.632569101162728, 0.01350920018934639, 0.05, -6.632700246142225, 0.0026228995899227493, 0.05, -6.632700246142225, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurLeftRightProfile.csv b/RoboRIO/src/main/resources/balbasaurLeftRightProfile.csv deleted file mode 100644 index 8e41378f..00000000 --- a/RoboRIO/src/main/resources/balbasaurLeftRightProfile.csv +++ /dev/null @@ -1,115 +0,0 @@ -114 -3.699747832301106E-4, 0.014798991329204423, 0.05, -0.0017202037817396815, 0.027004579970191414, 0.05, -0.00475812203587661, 0.06075836508273857, 0.05, -0.010158533879707679, 0.10800823687662138, 0.05, -0.01859582667426142, 0.16874585589107483, 0.05, -0.030406291566599162, 0.23620929784675482, 0.05, -0.04558817849312641, 0.30363773853054493, 0.05, -0.06413923038005531, 0.3710210377385779, 0.05, -0.0860566777414328, 0.4383489472275498, 0.05, -0.11133723219961533, 0.5056110891636505, 0.05, -0.13997707895893885, 0.5727969351864702, 0.05, -0.17197186815135915, 0.6398957838484057, 0.05, -0.2073167050711196, 0.7068967383952092, 0.05, -0.24600613932352272, 0.7737886850480621, 0.05, -0.28803415307247243, 0.8405602749789942, 0.05, -0.3333941484689513, 0.907199907929578, 0.05, -0.38207893408090554, 0.9736957122390846, 0.05, -0.43408071079435373, 1.0400355342689631, 0.05, -0.48939105680069866, 1.1062069201268983, 0.05, -0.548000912565019, 1.1721971152864081, 0.05, -0.6099005654640133, 1.237993057979886, 0.05, -0.6750796340995577, 1.3035813727108883, 0.05, -0.7435270533844289, 1.3689483856974245, 0.05, -0.8152310599371286, 1.4340801310539932, 0.05, -0.8901791786936479, 1.4989623751303862, 0.05, -0.9683582108888887, 1.5635806439048163, 0.05, -1.0497542244592901, 1.6279202714080276, 0.05, -1.1343525467845543, 1.6919664465052837, 0.05, -1.22213776149614, 1.7557042942317143, 0.05, -1.3130937093931359, 1.8191189579399176, 0.05, -1.4072034953642127, 1.8821957194215369, 0.05, -1.5044495018050716, 1.9449201288171774, 0.05, -1.6048134103820755, 2.007278171540078, 0.05, -1.7082762340346989, 2.0692564730524654, 0.05, -1.8148183601426033, 2.1308425221580904, 0.05, -1.9244196081216316, 2.192024959580563, 0.05, -2.0370593025867247, 2.252793889301865, 0.05, -2.1527163655807953, 2.3131412598814145, 0.05, -2.2713694299522964, 2.3730612874300236, 0.05, -2.3929969770975523, 2.4325509429051184, 0.05, -2.517577502069975, 2.4916104994484525, 0.05, -2.645089709186351, 2.5502441423275193, 0.05, -2.7755127412258798, 2.6084606407905775, 0.05, -2.908826445086827, 2.66627407721894, 0.05, -3.0450116765951587, 2.7237046301666394, 0.05, -3.184050646095636, 2.780779390009546, 0.05, -3.3259273064665313, 2.837533207417902, 0.05, -3.4706277827588745, 2.8940095258468626, 0.05, -3.618140842413405, 2.9502611930906086, 0.05, -3.7684584019251433, 3.0063511902347626, 0.05, -3.921576064165871, 3.0623532448145467, 0.05, -4.077493677443126, 3.118352265545102, 0.05, -4.235901938858177, 3.1681652283010218, 0.05, -4.396186007992297, 3.2056813826823887, 0.05, -4.557740986568064, 3.2310995715153417, 0.05, -4.7199709318537275, 3.2445989057132834, 0.05, -4.882070122769611, 3.2419838183176695, 0.05, -5.043239613257579, 3.2233898097593614, 0.05, -5.202901690060124, 3.1932415360509094, 0.05, -5.360479780594432, 3.1515618106861587, 0.05, -5.515396331503415, 3.0983310181796413, 0.05, -5.667287673020092, 3.0378268303335387, 0.05, -5.816096948151878, 2.976185502635721, 0.05, -5.96185684798373, 2.9151979966370547, 0.05, -6.104595278160761, 2.8547686035406064, 0.05, -6.244335471642774, 2.7948038696402593, 0.05, -6.381096167812986, 2.7352139234042414, 0.05, -6.514891846081663, 2.675913565373534, 0.05, -6.645733000828223, 2.6168230949311866, 0.05, -6.773626446819133, 2.557868919818197, 0.05, -6.8985756428632845, 2.4989839208830267, 0.05, -7.020581025394532, 2.440107650624942, 0.05, -7.13964034231811, 2.3811863384715664, 0.05, -7.2557489814220855, 2.3221727820795075, 0.05, -7.368900286459194, 2.2630261007421724, 0.05, -7.479085858519643, 2.2037114412089776, 0.05, -7.586295837581015, 2.1441995812274373, 0.05, -7.690519164226419, 2.0844665329080865, 0.05, -7.7917438190568875, 2.024493096609362, 0.05, -7.889957040232173, 1.9642644235057172, 0.05, -7.985145519398787, 1.903769583332277, 0.05, -8.077295575797478, 1.8430011279738119, 0.05, -8.166393310939855, 1.7819547028475307, 0.05, -8.25242474393698, 1.7206286599424858, 0.05, -8.335375929518685, 1.6590237116341362, 0.05, -8.415233060061732, 1.5971426108609266, 0.05, -8.491982552873521, 1.5349898562357949, 0.05, -8.565611124467953, 1.4725714318886165, 0.05, -8.63610585330696, 1.4098945767801248, 0.05, -8.703454232002873, 1.3469675739182454, 0.05, -8.767644210534087, 1.2837995706242693, 0.05, -8.828664231537743, 1.2204004200731373, 0.05, -8.886503258685586, 1.1567805429568672, 0.05, -8.94115079935905, 1.0929508134693018, 0.05, -8.992596921953206, 1.028922451883127, 0.05, -9.040832269443781, 0.9647069498115025, 0.05, -9.085848068728229, 0.9003159856889728, 0.05, -9.127636137983334, 0.8357613851020952, 0.05, -9.166188890609428, 0.7710550525218776, 0.05, -9.201499338018968, 0.7062089481907848, 0.05, -9.233561090408921, 0.6412350477990819, 0.05, -9.262368357179092, 0.5761453354034296, 0.05, -9.287915945360279, 0.5109517636237201, 0.05, -9.310199258577692, 0.44566626434823703, 0.05, -9.329214295106524, 0.38030073057666075, 0.05, -9.344957645955967, 0.3148670169888472, 0.05, -9.357426492842796, 0.2493769377366004, 0.05, -9.366618606495242, 0.18384227304891074, 0.05, -9.372760892700002, 0.12284572409518284, 0.05, -9.37640889584498, 0.07296006289957173, 0.05, -9.378218146839556, 0.03618501989151429, 0.05, -9.378844498015141, 0.012527023511690528, 0.05, -9.378943943498598, 0.001988909669147751, 0.05, -9.378943943498598, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightBackupBlueProfile.csv b/RoboRIO/src/main/resources/balbasaurRightBackupBlueProfile.csv deleted file mode 100644 index c3c67737..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightBackupBlueProfile.csv +++ /dev/null @@ -1,81 +0,0 @@ -80 -3.6982739809204466E-4, 0.014793095923681785, 0.05, -0.0031996979503669926, 0.05659741104549896, 0.05, -0.009578603910245242, 0.12757811919756498, 0.05, -0.020959112112158805, 0.22761016403827122, 0.05, -0.038845320109513595, 0.35772415994709583, 0.05, -0.06410276341902815, 0.5051488661902912, 0.05, -0.09695610550365885, 0.6570668416926138, 0.05, -0.137705402044716, 0.814985930821143, 0.05, -0.18673413764897642, 0.9805747120852083, 0.05, -0.24451820628610052, 1.155681372742482, 0.05, -0.31163453514741996, 1.3423265772263884, 0.05, -0.3887668454726832, 1.542646206505265, 0.05, -0.4767039550130393, 1.7587421908071215, 0.05, -0.5763228025113933, 1.9923769499670811, 0.05, -0.6885438711342353, 2.2444213724568387, 0.05, -0.8142417515342011, 2.5139576079993144, 0.05, -0.9540912856279344, 2.796990681874667, 0.05, -1.1083372454854272, 3.084919197149857, 0.05, -1.2765037757662336, 3.3633306056161265, 0.05, -1.4571153959166725, 3.612232403008777, 0.05, -1.6475654174665397, 3.8090004309973433, 0.05, -1.84427943522774, 3.9342803552240073, 0.05, -2.043215430445215, 3.978719904349496, 0.05, -2.240547800606715, 3.946647403229995, 0.05, -2.4332567158236147, 3.8541783043379905, 0.05, -2.619410941585074, 3.723084515229185, 0.05, -2.7981236670040364, 3.5742545083792407, 0.05, -2.9693067425514554, 3.423661510948384, 0.05, -3.133371654439959, 3.2812982377700695, 0.05, -3.2909709029999012, 3.1519849711988415, 0.05, -3.442811296207917, 3.0368078641603184, 0.05, -3.5895332033982505, 2.934438143806665, 0.05, -3.731636183114657, 2.8420595943281293, 0.05, -3.8694306327199284, 2.75588899210542, 0.05, -4.002998461493564, 2.6713565754727195, 0.05, -4.131775795113183, 2.575546672392368, 0.05, -4.254619257798641, 2.456869253709172, 0.05, -4.370184254933469, 2.311299942696561, 0.05, -4.476853654917845, 2.1333879996875096, 0.05, -4.572540987700413, 1.9137466556513696, 0.05, -4.654821565480072, 1.645611555593172, 0.05, -4.72100692579334, 1.3237072062653543, 0.05, -4.768046482080994, 0.940791125753088, 0.05, -4.792780695216119, 0.4946842627025093, 0.05, -4.79307663668823, 0.005918829442227619, 0.05, -4.819532902984684, 0.5291253259290742, 0.05, -4.8707775292745366, 1.0248925257970503, 0.05, -4.94125089672844, 1.4094673490780762, 0.05, -5.021254681369856, 1.6000756928283224, 0.05, -5.09944231216848, 1.5637526159724784, 0.05, -5.166531287240285, 1.3417795014360918, 0.05, -5.21753168191944, 1.020007893583103, 0.05, -5.25149661327503, 0.6792986271117991, 0.05, -5.269981391246409, 0.3696955594275714, 0.05, -5.275575249151184, 0.11187715809550569, 0.05, -5.280148321307221, 0.09146144312073973, 0.05, -5.292435053119973, 0.24573463625503325, 0.05, -5.310378417991883, 0.35886729743820384, 0.05, -5.33231018754623, 0.43863539108694255, 0.05, -5.3568977125886414, 0.4917505008482262, 0.05, -5.383081758523673, 0.5236809187006309, 0.05, -5.41002003927186, 0.5387656149637303, 0.05, -5.437040551357787, 0.5404102417185443, 0.05, -5.463604635984948, 0.5312816925432365, 0.05, -5.489278334607863, 0.5134739724582912, 0.05, -5.513710370034317, 0.4886407085290729, 0.05, -5.536615266804831, 0.4580979354102889, 0.05, -5.5577604014881326, 0.42290269366603395, 0.05, -5.576956050285417, 0.3839129759456905, 0.05, -5.594047719092108, 0.34183337613382503, 0.05, -5.608910229620112, 0.29725021056008355, 0.05, -5.621443160957745, 0.25065862675266537, 0.05, -5.63156735698193, 0.20248392048368719, 0.05, -5.639222279203649, 0.1530984444343729, 0.05, -5.6444873377705544, 0.10530117133811469, 0.05, -5.647714143693477, 0.06453611845845621, 0.05, -5.649400990008964, 0.03373692630973543, 0.05, -5.65005506341408, 0.013081468102329859, 0.05, -5.650187680525016, 0.0026523422187159367, 0.05, -5.650187680525016, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightBackupRedProfile.csv b/RoboRIO/src/main/resources/balbasaurRightBackupRedProfile.csv deleted file mode 100644 index 273df796..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightBackupRedProfile.csv +++ /dev/null @@ -1,77 +0,0 @@ -76 -3.6656246461197776E-4, 0.01466249858447911, 0.05, -0.002686458269174325, 0.04639791609124694, 0.05, -0.007910604561912163, 0.10448292585475676, 0.05, -0.017213000227268415, 0.18604791330712503, 0.05, -0.031786697890584144, 0.29147395326631453, 0.05, -0.052269804738410364, 0.4096621369565244, 0.05, -0.0787437373061971, 0.5294786513557348, 0.05, -0.1113152461787909, 0.6514301774518761, 0.05, -0.15011786352005688, 0.7760523468253192, 0.05, -0.19531350891536714, 0.9039129079062053, 0.05, -0.24709409533887777, 1.0356117284702129, 0.05, -0.30568286970981734, 1.171775487418791, 0.05, -0.37133507344654715, 1.3130440747345955, 0.05, -0.4443372902767593, 1.4600443366042426, 0.05, -0.5250045425471809, 1.6133450454084315, 0.05, -0.6136738049902354, 1.7733852488610906, 0.05, -0.7106921363390486, 1.940366626976265, 0.05, -0.8163971738405283, 2.114100750029595, 0.05, -0.9310874832515302, 2.293806188220037, 0.05, -1.0549805747653287, 2.477861830275968, 0.05, -1.188157851459578, 2.6635455338849887, 0.05, -1.330498979697603, 2.8468225647604974, 0.05, -1.4816134951965574, 3.0222903099790854, 0.05, -1.6407840909250164, 3.1834119145691786, 0.05, -1.8069413007112574, 3.3231441957248187, 0.05, -1.9786888016675592, 3.4349500191260383, 0.05, -2.1543885283950908, 3.5139945345506343, 0.05, -2.332296131887955, 3.5581520698572877, 0.05, -2.510717862262286, 3.5684346074866222, 0.05, -2.6881506867748595, 3.548656490251468, 0.05, -2.863374205047729, 3.5044703654573897, 0.05, -3.035481353234769, 3.4421429637407974, 0.05, -3.203854242182049, 3.367457778945598, 0.05, -3.36759643148645, 3.274843786088024, 0.05, -3.5255976006331675, 3.160023382934352, 0.05, -3.6770251588054905, 3.0285511634464632, 0.05, -3.8212252833029976, 2.8840024899501375, 0.05, -3.957348045036942, 2.7224552346788826, 0.05, -4.084664119028874, 2.5463214798386384, 0.05, -4.20279821551423, 2.3626819297071173, 0.05, -4.311394317212427, 2.1719220339639467, 0.05, -4.410133137097534, 1.9747763977021549, 0.05, -4.49897599804836, 1.7768572190165162, 0.05, -4.578186365446667, 1.5842073479661503, 0.05, -4.648074057948823, 1.3977538500431121, 0.05, -4.708944631628196, 1.2174114735874622, 0.05, -4.761132381642081, 1.0437550002777103, 0.05, -4.805030366291078, 0.8779596929799283, 0.05, -4.841115339384625, 0.7216994618709345, 0.05, -4.869964545524921, 0.5769841228059274, 0.05, -4.892261028564089, 0.44592966078336876, 0.05, -4.908784828120274, 0.3304759911237019, 0.05, -4.920389360604619, 0.23209064968690185, 0.05, -4.927965096188433, 0.15151471167626585, 0.05, -4.932395527836566, 0.08860863296267607, 0.05, -4.9345123194435665, 0.042335832140016356, 0.05, -4.9350566365002875, 0.010886341134417327, 0.05, -4.9354613873741595, 0.008095017477443284, 0.05, -4.936322834855619, 0.017228949629194835, 0.05, -4.937279801513981, 0.019139333167227403, 0.05, -4.938091753840666, 0.016239046533717265, 0.05, -4.938621426206393, 0.01059344731454384, 0.05, -4.938814217190906, 0.003855819690250409, 0.05, -4.9389511597784335, 0.0027388517505474268, 0.05, -4.93936819378603, 0.008340680151932893, 0.05, -4.939989772988188, 0.012431584043165946, 0.05, -4.9407279808746445, 0.014764157729140864, 0.05, -4.941493131516561, 0.015303012838327896, 0.05, -4.942201770821084, 0.014172786090461492, 0.05, -4.942782508334738, 0.01161475027307759, 0.05, -4.943197376052642, 0.008297354358083686, 0.05, -4.943453096777707, 0.005114414501289086, 0.05, -4.943581282225457, 0.0025637089550046535, 0.05, -4.9436246989997805, 8.683354864687143E-4, 0.05, -4.943631024992702, 1.2651985842556277E-4, 0.05, -4.943631024992702, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightBlueShootProfile.csv b/RoboRIO/src/main/resources/balbasaurRightBlueShootProfile.csv deleted file mode 100644 index 4ec3178d..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightBlueShootProfile.csv +++ /dev/null @@ -1,89 +0,0 @@ -88 -3.6985651373580244E-4, 0.014794260549432097, 0.05, -0.0023078566232521444, 0.03876000219032684, 0.05, -0.006668321855357661, 0.08720930464211032, 0.05, -0.014420132245550304, 0.15503620780385285, 0.05, -0.026531975284867837, 0.24223686078635065, 0.05, -0.043487713017484976, 0.33911475465234275, 0.05, -0.06528625792725755, 0.4359708981954514, 0.05, -0.09192586082705731, 0.5327920579959953, 0.05, -0.12340384544071782, 0.6295596922732102, 0.05, -0.1597162833948434, 0.7262487590825115, 0.05, -0.20085760896476673, 0.822826511398467, 0.05, -0.2468201741920785, 0.9192513045462354, 0.05, -0.2975937473267214, 1.0154714626928576, 0.05, -0.3531649576520435, 1.1114242065064421, 0.05, -0.4135166929593369, 1.2070347061458682, 0.05, -0.4786274575094929, 1.30221529100312, 0.05, -0.5484707029928638, 1.3968649096674186, 0.05, -0.6230141459206912, 1.4908688585565462, 0.05, -0.7022190912096554, 1.5840989057792858, 0.05, -0.7860397824315227, 1.6764138244373465, 0.05, -0.8744228045312393, 1.7676604419943325, 0.05, -0.9673065655812081, 1.8576752209993743, 0.05, -1.0646208858525734, 1.9462864054273077, 0.05, -1.1662867221045583, 2.0333167250396955, 0.05, -1.2722160518497843, 2.1185865949045177, 0.05, -1.3823119382209728, 2.201917727423769, 0.05, -1.4964687883691314, 2.283137002963174, 0.05, -1.614572809358922, 2.3620804197958116, 0.05, -1.7365026543243072, 2.438596899307701, 0.05, -1.8621302396890917, 2.5125517072956907, 0.05, -1.9913217021879626, 2.583829249977415, 0.05, -2.12393845341821, 2.652335024604947, 0.05, -2.25983828073516, 2.7179965463389992, 0.05, -2.3988764373273974, 2.78076313184475, 0.05, -2.540906662093673, 2.840604495325505, 0.05, -2.685782071340629, 2.897508184939124, 0.05, -2.833355869579451, 2.9514759647764435, 0.05, -2.9834818348882433, 3.0025193061758415, 0.05, -3.1360145448501946, 3.0506541992390224, 0.05, -3.2903991138806328, 3.087691380608768, 0.05, -3.4456970705649947, 3.1059591336872394, 0.05, -3.6010125765477734, 3.106310119655576, 0.05, -3.755492344992845, 3.08959536890143, 0.05, -3.908116639126907, 3.0524858826812444, 0.05, -4.057917367615993, 2.996014569781729, 0.05, -4.204179004470296, 2.925232737086059, 0.05, -4.346223046968459, 2.840880849963253, 0.05, -4.483406317713025, 2.74366541489134, 0.05, -4.615314175873921, 2.6381571632179193, 0.05, -4.741913697494917, 2.531990432419922, 0.05, -4.863340028032593, 2.428526610753512, 0.05, -4.979723157570135, 2.3276625907508373, 0.05, -5.0911885828366366, 2.2293085053300348, 0.05, -5.197857881659352, 2.133385976454306, 0.05, -5.299849186157841, 2.039826089969796, 0.05, -5.397277548253787, 1.948567241918915, 0.05, -5.490255196764743, 1.8595529702191138, 0.05, -5.57889169009416, 1.7727298665883517, 0.05, -5.6632939721420525, 1.6880456409578488, 0.05, -5.743566342151568, 1.6054474001903032, 0.05, -5.819810351410296, 1.5248801851745657, 0.05, -5.892124641321361, 1.4462857982213062, 0.05, -5.960604738273309, 1.3696019390389613, 0.05, -6.0253428209114555, 1.2947616527629202, 0.05, -6.086427474938339, 1.2216930805376707, 0.05, -6.143943449502993, 1.1503194912930887, 0.05, -6.19797142762789, 1.0805595624979447, 0.05, -6.248587821083074, 1.0123278691036837, 0.05, -6.2958645977903, 0.9455355341445107, 0.05, -6.339869147382403, 0.8800909918420685, 0.05, -6.380664188058946, 0.815900813530838, 0.05, -6.418307715509586, 0.7528705490128074, 0.05, -6.452852992560978, 0.6909055410278344, 0.05, -6.484348576332487, 0.629911675430176, 0.05, -6.512838378250248, 0.5697960383552232, 0.05, -6.538361751132554, 0.5104674576461107, 0.05, -6.560953596866199, 0.4518369146729002, 0.05, -6.5806444878029176, 0.39381781873438504, 0.05, -6.597460795008206, 0.3363261441057587, 0.05, -6.61142481663689, 0.27928043257368595, 0.05, -6.622554900308808, 0.22260167343835285, 0.05, -6.630865553825049, 0.1662130703248184, 0.05, -6.636517246773392, 0.11303385896686985, 0.05, -6.639946232856611, 0.06857972166437135, 0.05, -6.641715314173481, 0.03538162633740166, 0.05, -6.64238508682488, 0.013395453027980272, 0.05, -6.642515127292425, 0.0026008093509019884, 0.05, -6.642515127292425, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightLeftProfile.csv b/RoboRIO/src/main/resources/balbasaurRightLeftProfile.csv deleted file mode 100644 index 42df79c3..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightLeftProfile.csv +++ /dev/null @@ -1,115 +0,0 @@ -114 -3.699747832301106E-4, 0.014798991329204423, 0.05, -0.0017166991833346924, 0.026934488002091632, 0.05, -0.004746729470140093, 0.06060060573610802, 0.05, -0.01013310929632102, 0.10772759652361852, 0.05, -0.018548454073226094, 0.1683068955381015, 0.05, -0.030328144582440257, 0.23559381018428327, 0.05, -0.04547038346773698, 0.3028447777059344, 0.05, -0.063972852658592, 0.3700493838171004, 0.05, -0.08583270782535614, 0.43719710333528283, 0.05, -0.11104657172563473, 0.5042772780055719, 0.05, -0.13961052647309388, 0.5712790949491828, 0.05, -0.17152010464844553, 0.638191563507033, 0.05, -0.20677027927062214, 0.705003492443532, 0.05, -0.24535545265439204, 0.7717034676753979, 0.05, -0.2872694443402349, 0.8382798337168569, 0.05, -0.3325054781804179, 0.9047206768036612, 0.05, -0.38105616840479256, 0.9710138044874924, 0.05, -0.4329135051379885, 1.037146734663918, 0.05, -0.48806883898797304, 1.1031066769996911, 0.05, -0.5465128656030438, 1.168880532301414, 0.05, -0.608235609892599, 1.2344548857911035, 0.05, -0.6732264099247587, 1.2998160006431954, 0.05, -0.7414739016028149, 1.3649498335611234, 0.05, -0.8129660036690062, 1.4298420413238246, 0.05, -0.8876899039531512, 1.4944780056829006, 0.05, -0.9656320470330068, 1.5588428615971122, 0.05, -1.04677812437209, 1.6229215467816651, 0.05, -1.1311130668735419, 1.6866988500290372, 0.05, -1.2186210415964398, 1.7501594944579593, 0.05, -1.3092854527030207, 1.8132882221316187, 0.05, -1.4030889485621432, 1.8760699171824484, 0.05, -1.5000134355344714, 1.9384897394465639, 0.05, -1.6000401003273745, 2.0005332958580637, 0.05, -1.7031494428552716, 2.0621868505579415, 0.05, -1.8093213205841123, 2.1234375545768156, 0.05, -1.918535007676121, 2.1842737418401716, 0.05, -2.0307692701388333, 2.244685249254251, 0.05, -2.146002460542368, 2.3046638080706927, 0.05, -2.2642126344639353, 2.364203478431348, 0.05, -2.3853776919536966, 2.423301149795228, 0.05, -2.5094755471070234, 2.4819571030665304, 0.05, -2.6364843289578306, 2.5401756370161426, 0.05, -2.7663826168720353, 2.597965758284091, 0.05, -2.899149713384786, 2.65534193025501, 0.05, -3.034765957244021, 2.712324877184704, 0.05, -3.1732130783450283, 2.7689424220201477, 0.05, -3.314474596224133, 2.8252303575820914, 0.05, -3.4585362613121333, 2.881233301760008, 0.05, -3.605386537852288, 2.9370055308030927, 0.05, -3.755017124255575, 2.992611728065749, 0.05, -3.907423504938548, 3.048127613659458, 0.05, -4.062605524483561, 3.1036403909002677, 0.05, -4.2202555196166385, 3.1529999026615556, 0.05, -4.379762030423889, 3.190130216145005, 0.05, -4.5405238076373795, 3.2152355442698166, 0.05, -4.701948799396699, 3.2284998351863847, 0.05, -4.863236473082524, 3.2257534737165, 0.05, -5.023593254101174, 3.2071356203730015, 0.05, -5.182445812484906, 3.177051167674654, 0.05, -5.3392219898113185, 3.1355235465282396, 0.05, -5.493348620474676, 3.0825326132671593, 0.05, -5.644465235790836, 3.0223323063232037, 0.05, -5.792516473413523, 2.961024752453734, 0.05, -5.937535908017307, 2.9003886920756887, 0.05, -6.0795521995470185, 2.8403258305942214, 0.05, -6.218589209009977, 2.7807401892591668, 0.05, -6.35466618242383, 2.721539468277058, 0.05, -6.487797990722273, 2.66263616596886, 0.05, -6.617995412130341, 2.6039484281613703, 0.05, -6.745265445820593, 2.545400673805028, 0.05, -6.869611644322711, 2.4869239700423518, 0.05, -6.9910344561066955, 2.4284562356797013, 0.05, -7.109531568457232, 2.369942247010729, 0.05, -7.225098244747634, 2.3113335258080356, 0.05, -7.33772764907629, 2.2525880865731196, 0.05, -7.447411155764384, 2.1936701337618825, 0.05, -7.554138638529784, 2.13454965530798, 0.05, -7.657898739266369, 2.0752020147317176, 0.05, -7.75867911393248, 2.0156074933222157, 0.05, -7.856466655969858, 1.9557508407475512, 0.05, -7.951247697518608, 1.8956208309749916, 0.05, -8.043008188242851, 1.8352098144848545, 0.05, -8.131733854178375, 1.7745133187104851, 0.05, -8.217410336723809, 1.7135296509086695, 0.05, -8.300023313848776, 1.6522595424993227, 0.05, -8.379558604877312, 1.590705820570733, 0.05, -8.456002260134365, 1.5288731051410547, 0.05, -8.529340637230273, 1.466767541918155, 0.05, -8.599560465494823, 1.4043965652909878, 0.05, -8.666648899593556, 1.3417686819746402, 0.05, -8.730593563911562, 1.2788932863601372, 0.05, -8.791382588800253, 1.2157804977738356, 0.05, -8.849004639722217, 1.1524410184392782, 0.05, -8.903448940535407, 1.088886016263782, 0.05, -8.954705291271875, 1.0251270147293696, 0.05, -9.002764082063205, 0.961175815826621, 0.05, -9.047616302746748, 0.8970444136708781, 0.05, -9.089253550405841, 0.8327449531818749, 0.05, -9.127668033435949, 0.7682896606021544, 0.05, -9.16285257440083, 0.7036908192976122, 0.05, -9.194800610834001, 0.6389607286634311, 0.05, -9.2235061956527, 0.5741116963739884, 0.05, -9.2489639955636, 0.5091559982179829, 0.05, -9.271169289984796, 0.44410588842391713, 0.05, -9.290117969053119, 0.37897358136645615, 0.05, -9.305806531655517, 0.31377125204793915, 0.05, -9.318232083351022, 0.24851103391010645, 0.05, -9.327392334626467, 0.18320502550887421, 0.05, -9.333513356036999, 0.12242042821063012, 0.05, -9.337148739547327, 0.07270767020655262, 0.05, -9.338951734479355, 0.03605989864054513, 0.05, -9.339575920267283, 0.012483715758541382, 0.05, -9.339675021973088, 0.001982034116091337, 0.05, -9.339675021973088, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightMidProfile.csv b/RoboRIO/src/main/resources/balbasaurRightMidProfile.csv deleted file mode 100644 index c1ba2db4..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightMidProfile.csv +++ /dev/null @@ -1,91 +0,0 @@ -90 -3.741923350751432E-4, 0.014967693403005728, 0.05, -0.0018709616753757154, 0.029935386806011443, 0.05, -0.005238692691051996, 0.0673546203135256, 0.05, -0.011225770052254273, 0.11974154722404554, 0.05, -0.02058057842913283, 0.1870961675375711, 0.05, -0.03367731015676313, 0.26193463455260596, 0.05, -0.05051596523514526, 0.33677310156764256, 0.05, -0.07109654366427896, 0.41161156858267406, 0.05, -0.09541904544416427, 0.4864500355977061, 0.05, -0.12348347057480115, 0.5612885026127375, 0.05, -0.15528981905618963, 0.6361269696277696, 0.05, -0.19083809088832968, 0.7109654366428009, 0.05, -0.23012828607121433, 0.785803903657693, 0.05, -0.2731604046048427, 0.8606423706725674, 0.05, -0.31993444648922126, 0.9354808376875712, 0.05, -0.37045041172435017, 1.0103193047025782, 0.05, -0.42470830031023254, 1.0851577717176475, 0.05, -0.48270811224690224, 1.159996238733394, 0.05, -0.5444498475343247, 1.2348347057484488, 0.05, -0.6099335061725002, 1.3096731727635103, 0.05, -0.6791590881614286, 1.3845116397785673, 0.05, -0.7521265935011098, 1.4593501067936243, 0.05, -0.828836022191544, 1.5341885738086836, 0.05, -0.9092873742326351, 1.6090270408218221, 0.05, -0.9934806496244581, 1.6838655078364617, 0.05, -1.081415848367029, 1.7587039748514188, 0.05, -1.1730929704603472, 1.8335424418663626, 0.05, -1.2685120159044134, 1.9083809088813242, 0.05, -1.367672984699227, 1.9832193758962724, 0.05, -1.4705758768447885, 2.0580578429112295, 0.05, -1.5772206923410976, 2.132896309926182, 0.05, -1.6876074311881546, 2.2077347769411393, 0.05, -1.8017360933859592, 2.282573243956092, 0.05, -1.9196066789345116, 2.357411710971049, 0.05, -2.041219187833812, 2.432250177986006, 0.05, -2.1665736200838595, 2.50708864500095, 0.05, -2.2956699756846546, 2.5819271120159026, 0.05, -2.428508254636198, 2.656765579030864, 0.05, -2.5650884569384886, 2.731604046045817, 0.05, -2.705410582591527, 2.8064425130607695, 0.05, -2.8491004392602384, 2.873797133374225, 0.05, -2.995409642274473, 2.9261840602846956, 0.05, -3.1435898069640813, 2.963603293792163, 0.05, -3.2928925486589145, 2.986054833896663, 0.05, -3.4425372456733605, 2.992893940288921, 0.05, -3.5917432763212798, 2.9841206129583853, 0.05, -3.7397622559321424, 2.9603795922172527, 0.05, -3.8858457998357925, 2.9216708780730016, 0.05, -4.029245523362077, 2.8679944705256943, 0.05, -4.169245278856756, 2.799995109893594, 0.05, -4.305503111000667, 2.725156642878215, 0.05, -4.43801901979381, 2.6503181758628536, 0.05, -4.566793005236184, 2.5754797088474746, 0.05, -4.691825067327788, 2.5006412418320956, 0.05, -4.813115206068626, 2.425802774816752, 0.05, -4.9306634214586955, 2.350964307801391, 0.05, -5.044469713497994, 2.2761258407859764, 0.05, -5.154534082186526, 2.201287373770633, 0.05, -5.26085652752429, 2.1264489067552717, 0.05, -5.363437049511284, 2.0516104397398927, 0.05, -5.462275648147509, 1.976771972724496, 0.05, -5.557372323432968, 1.901933505709188, 0.05, -5.648727075367657, 1.8270950386937734, 0.05, -5.736339903951578, 1.7522565716784122, 0.05, -5.82021080918473, 1.677418104663051, 0.05, -5.900339791067116, 1.6025796376477075, 0.05, -5.976726849598729, 1.5277411706322752, 0.05, -6.049371984779578, 1.4529027036169673, 0.05, -6.118275196609655, 1.3780642366015528, 0.05, -6.183436485088967, 1.303225769586227, 0.05, -6.244855850217507, 1.2283873025708125, 0.05, -6.302533291995281, 1.153548835555469, 0.05, -6.356468810422285, 1.07871036854009, 0.05, -6.406662405498523, 1.0038719015247466, 0.05, -6.453114077223989, 0.9290334345093321, 0.05, -6.495823825598689, 0.8541949674939886, 0.05, -6.534791650622619, 0.7793565004786096, 0.05, -6.570017552295782, 0.7045180334632661, 0.05, -6.601501530618175, 0.6296795664478516, 0.05, -6.629243585589801, 0.5548410994325259, 0.05, -6.653243717210658, 0.48000263241712915, 0.05, -6.673501925480747, 0.4051641654017857, 0.05, -6.6900182104000665, 0.3303256983863889, 0.05, -6.702792571968618, 0.2554872313710277, 0.05, -6.711857247202316, 0.1812935046739561, 0.05, -6.717618665452148, 0.11522836499665345, 0.05, -6.720825211388272, 0.06413091872246923, 0.05, -6.722225269680838, 0.028001165851314624, 0.05, -6.722567225, 0.006839106383242921, 0.05, -6.722567225, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightRedShootProfile.csv b/RoboRIO/src/main/resources/balbasaurRightRedShootProfile.csv deleted file mode 100644 index 60f9bf9c..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightRedShootProfile.csv +++ /dev/null @@ -1,89 +0,0 @@ -88 -3.6985651373580244E-4, 0.014794260549432097, 0.05, -0.001402776174051248, 0.020658393206308908, 0.05, -0.003726879583993615, 0.046482068198847336, 0.05, -0.007858742777397818, 0.08263726386808407, 0.05, -0.014315128420285272, 0.12912771285774904, 0.05, -0.023354884520931755, 0.18079512201292963, 0.05, -0.03497906580539897, 0.23248362568934428, 0.05, -0.049189370331490644, 0.28420609052183343, 0.05, -0.06598839739383777, 0.33598054124694243, 0.05, -0.08537996437979224, 0.38783133971908945, 0.05, -0.10736948210530048, 0.43979035451016485, 0.05, -0.13196438762302323, 0.4918981103544551, 0.05, -0.15917463293066927, 0.5442049061529206, 0.05, -0.18901322558410966, 0.5967718530688079, 0.05, -0.22149681574249686, 0.6496718031677441, 0.05, -0.2566463211072909, 0.7029901072958807, 0.05, -0.29448757917021845, 0.7568251612585506, 0.05, -0.335052011617367, 0.8112886489429708, 0.05, -0.3783772838275432, 0.8665054442035253, 0.05, -0.4245079375679103, 0.9226130748073417, 0.05, -0.4734959732418558, 0.979760713478911, 0.05, -0.5254013549874278, 1.03810763491144, 0.05, -0.5802924111957204, 1.0978211241658515, 0.05, -0.6382461036300341, 1.1590738486862744, 0.05, -0.6993481404642115, 1.2220407366835466, 0.05, -0.7636929136188206, 1.2868954630921847, 0.05, -0.8313832474260144, 1.3538066761438752, 0.05, -0.9025299549239629, 1.4229341499589703, 0.05, -0.9772512087258293, 1.4944250760373272, 0.05, -1.0556717451472168, 1.56841072842775, 0.05, -1.1379219320120366, 1.6450037372963937, 0.05, -1.2241367413039694, 1.7242961858386574, 0.05, -1.31445467653336, 1.8063587045878096, 0.05, -1.409016710432586, 1.8912406779845192, 0.05, -1.5079652909227694, 1.9789716098036718, 0.05, -1.6114434717441783, 2.069563616428178, 0.05, -1.7195942191807359, 2.16301494873115, 0.05, -1.8325599382310669, 2.2593143810066194, 0.05, -1.95048225134889, 2.358446262356461, 0.05, -2.073171494661735, 2.4537848662569006, 0.05, -2.2000815106331935, 2.538200319429166, 0.05, -2.3306246087002545, 2.6108619613412234, 0.05, -2.4641716464874723, 2.6709407557443554, 0.05, -2.599865053650362, 2.713868143257793, 0.05, -2.736796959216591, 2.738638111324581, 0.05, -2.8742040481687368, 2.7481417790429177, 0.05, -3.011286956712407, 2.7416581708734133, 0.05, -3.147211930206812, 2.718499469888094, 0.05, -3.2813131828584368, 2.6820250530324956, 0.05, -3.4132832472825108, 2.6394012884814813, 0.05, -3.542990515820021, 2.5941453707502053, 0.05, -3.6703084079529646, 2.546357842658872, 0.05, -3.7951147243051935, 2.4961263270445775, 0.05, -3.9172910860980674, 2.443527235857482, 0.05, -4.036722473366539, 2.388627745369436, 0.05, -4.153296868195498, 2.3314878965791697, 0.05, -4.26690500356677, 2.2721627074254567, 0.05, -4.377440214035604, 2.210704209376677, 0.05, -4.484798380663733, 2.1471633325625805, 0.05, -4.588877959871484, 2.0815915841550185, 0.05, -4.689580083577134, 2.0140424741130003, 0.05, -4.786808716470173, 1.9445726578607658, 0.05, -4.88047085543763, 1.8732427793491484, 0.05, -4.970476755941059, 1.8001180100685676, 0.05, -5.056740170587887, 1.7252682929365653, 0.05, -5.139178586212944, 1.6487683125011368, 0.05, -5.217713447358844, 1.5706972229179894, 0.05, -5.2922703560122955, 1.4911381730690259, 0.05, -5.362779239704153, 1.4101776738371536, 0.05, -5.4291744825021775, 1.3279048559604933, 0.05, -5.491395015832021, 1.244410666596875, 0.05, -5.549384368349376, 1.1597870503471015, 0.05, -5.603090676202273, 1.0741261570579441, 0.05, -5.65246665675314, 0.9875196110173549, 0.05, -5.697469550335678, 0.9000578716507592, 0.05, -5.738061035634809, 0.8118297059826066, 0.05, -5.774207125023397, 0.722921787771759, 0.05, -5.805878046503619, 0.6334184296044348, 0.05, -5.833048119019127, 0.5434014503101594, 0.05, -5.855695627534676, 0.4529501703109837, 0.05, -5.873802704058431, 0.3621415304750983, 0.05, -5.8873552198839185, 0.27105031650975037, 0.05, -5.896587408922838, 0.1846437807783933, 0.05, -5.9021949591550555, 0.1121510046443504, 0.05, -5.905089838451588, 0.05789758593065891, 0.05, -5.90618616295801, 0.021926490128433604, 0.05, -5.9063990418219205, 0.004257577278221297, 0.05, -5.9063990418219205, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/balbasaurRightRightProfile.csv b/RoboRIO/src/main/resources/balbasaurRightRightProfile.csv deleted file mode 100644 index 141e63c0..00000000 --- a/RoboRIO/src/main/resources/balbasaurRightRightProfile.csv +++ /dev/null @@ -1,115 +0,0 @@ -114 -3.699747832301106E-4, 0.014798991329204423, 0.05, -0.001979544063773239, 0.032191385610862565, 0.05, -0.005601171900384665, 0.07243255673222851, 0.05, -0.012039953050355552, 0.12877562299941775, 0.05, -0.022101399150928715, 0.2012289220114632, 0.05, -0.03618916839438763, 0.2817553848691782, 0.05, -0.05430501037195731, 0.3623168395513937, 0.05, -0.07645118176840514, 0.4429234279289565, 0.05, -0.10263045153114222, 0.5235853952547418, 0.05, -0.13284610727418475, 0.6043131148608505, 0.05, -0.16710196291151042, 0.6851171127465133, 0.05, -0.205402367366947, 0.766008089108732, 0.05, -0.24775221430795064, 0.8469969388200727, 0.05, -0.29415695283922966, 0.9280947706255801, 0.05, -0.34462259925809996, 1.009312928377406, 0.05, -0.3991557498204112, 1.0906630112462243, 0.05, -0.4577635941133118, 1.1721568858580116, 0.05, -0.5204539293654444, 1.2538067050426538, 0.05, -0.5872351749424123, 1.3356249115393581, 0.05, -0.65811638775123, 1.4176242561763557, 0.05, -0.7331072777487728, 1.4998177999508544, 0.05, -0.8122182230347563, 1.5822189057196696, 0.05, -0.8954602852240009, 1.6648412437848916, 0.05, -0.9828452237783695, 1.7476987710873721, 0.05, -1.0743855094906076, 1.8308057142447638, 0.05, -1.17009433622442, 1.914176534676247, 0.05, -1.2699856309125315, 1.997825893762229, 0.05, -1.3740740602000188, 2.081768585749747, 0.05, -1.4823750340746145, 2.166019477491912, 0.05, -1.594904704462572, 2.25059340775915, 0.05, -1.7116799587185323, 2.335505085119206, 0.05, -1.8327184058309607, 2.4207689422485665, 0.05, -1.9580383544318418, 2.506398972017622, 0.05, -2.0876587813146754, 2.5924085376566706, 0.05, -2.2215992874737807, 2.678810123182104, 0.05, -2.3598800410930076, 2.765615072384541, 0.05, -2.5025217037350997, 2.8528332528418385, 0.05, -2.6495453384298484, 2.940472693894977, 0.05, -2.800972296097615, 3.028539153355331, 0.05, -2.9568240777509134, 3.117035633065964, 0.05, -3.117122169338054, 3.205961831742813, 0.05, -3.2818878461084355, 3.2953135354076277, 0.05, -3.4511419434241204, 3.385081946313697, 0.05, -3.6249045910541873, 3.47525295260134, 0.05, -3.803194908598543, 3.5658063508871143, 0.05, -3.9860306596629393, 3.656715021287929, 0.05, -4.173427864429856, 3.747944095338327, 0.05, -4.365400369847312, 3.839450108349125, 0.05, -4.5619593799697356, 3.931180202448461, 0.05, -4.763112949511078, 4.023071390826852, 0.05, -4.968865447029946, 4.115049950377355, 0.05, -5.1792169964974955, 4.207030989350992, 0.05, -5.393736962782622, 4.290399325702528, 0.05, -5.6115603481088066, 4.356467706523696, 0.05, -5.831812227496243, 4.4050375877487316, 0.05, -6.05360873373391, 4.435930124753328, 0.05, -6.275760199675879, 4.443029318839396, 0.05, -6.497070190894484, 4.426199824372091, 0.05, -6.7166366306896945, 4.391328795904206, 0.05, -6.933556298608535, 4.338393358376806, 0.05, -7.146926947693717, 4.267412981703653, 0.05, -7.356148028048714, 4.184421607099937, 0.05, -7.561052078853895, 4.098081016103626, 0.05, -7.761606405562983, 4.011086534181748, 0.05, -7.957783095642116, 3.923533801582648, 0.05, -8.149558906534864, 3.8355162178549778, 0.05, -8.336915086676383, 3.747123602830363, 0.05, -8.519837142743363, 3.6584411213395898, 0.05, -8.69831456453922, 3.569548435917148, 0.05, -8.872340520780002, 3.4805191248156047, 0.05, -9.041911534935764, 3.39142028311525, 0.05, -9.207027152765566, 3.302312356596022, 0.05, -9.367689608095267, 3.213249106594044, 0.05, -9.523903495404872, 3.124277746192101, 0.05, -9.675675452868482, 3.0354391492722086, 0.05, -9.823013862483936, 2.9467681923090807, 0.05, -9.96592856744821, 2.8582940992854433, 0.05, -10.104430611346766, 2.770040877971146, 0.05, -10.238531998340338, 2.6820277398714656, 0.05, -10.368245475721357, 2.594269547620389, 0.05, -10.493584338610404, 2.5067772577809366, 0.05, -10.614562254918717, 2.4195583261662432, 0.05, -10.731193111368476, 2.3326171289951794, 0.05, -10.843490877790904, 2.2459553284485634, 0.05, -10.951469489171691, 2.1595722276157323, 0.05, -11.055142743788632, 2.0734650923388434, 0.05, -11.154524215651225, 1.9876294372518548, 0.05, -11.249627180136484, 1.9020592897051674, 0.05, -11.340464551485391, 1.8167474269781365, 0.05, -11.427048830372762, 1.7316855777473998, 0.05, -11.509392060681318, 1.6468646061711045, 0.05, -11.587505794192305, 1.5622746702197388, 0.05, -11.661401062055228, 1.47790535725847, 0.05, -11.731088352389227, 1.3937458066799775, 0.05, -11.796577592452302, 1.309784801261486, 0.05, -11.857878135686956, 1.2260108646930916, 0.05, -11.914998751438336, 1.1424123150276024, 0.05, -11.967947618798338, 1.0589773472000248, 0.05, -12.016732321527352, 0.9756940545802918, 0.05, -12.061359845841599, 0.892550486284935, 0.05, -12.101836579033613, 0.8095346638402885, 0.05, -12.138168310212542, 0.7266346235785911, 0.05, -12.170360230395051, 0.6438384036501913, 0.05, -12.19841693453247, 0.5611340827483546, 0.05, -12.22234242313895, 0.4785097721296489, 0.05, -12.242140104269785, 0.3959536226166881, 0.05, -12.257812795314644, 0.31345382089717294, 0.05, -12.269362724865266, 0.23099859101245318, 0.05, -12.27707860584282, 0.1543176195511078, 0.05, -12.281660461951986, 0.09163712218332698, 0.05, -12.283932661575141, 0.04544399246309977, 0.05, -12.28471925143743, 0.01573179724577786, 0.05, -12.28484413646717, 0.0024977005947786996, 0.05, -12.28484413646717, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/ballbasaur_map.yml b/RoboRIO/src/main/resources/ballbasaur_map.yml index 9213f390..a9d72fa2 100644 --- a/RoboRIO/src/main/resources/ballbasaur_map.yml +++ b/RoboRIO/src/main/resources/ballbasaur_map.yml @@ -1,73 +1,15 @@ --- -doMP: true -testMP: false +doMP: false +testMP: true leftTestProfile: &leftTest '@id': leftTest - filename: "100InchProfile.csv" - inverted: false + filename: "ballbasaurForward100InProfile.csv" + inverted: true + velocityOnly: true rightTestProfile: <<: *leftTest '@id': rightTest -leftProfiles: !!map - "blue_center" : - '@id': blueLeftCenter - filename: "calciferLeftBlueMidProfile.csv" - inverted: false - "blue_left" : - '@id': blueLeftLeft - filename: "calciferLeftBlueLeftProfile.csv" - inverted: false - "blue_right" : - '@id': blueLeftRight - filename: "calciferLeftBlueRightProfile.csv" - inverted: false - "red_center" : - '@id': redLeftCenter - filename: "calciferLeftRedMidProfile.csv" - inverted: false - "red_left" : - '@id': redLeftLeft - filename: "calciferLeftRedLeftProfile.csv" - inverted: false - "red_right" : - '@id': redLeftRight - filename: "calciferLeftRedRightProfile.csv" - inverted: false -rightProfiles: !!map - "blue_center" : - '@id': blueRightCenter - filename: "calciferRightBlueMidProfile.csv" - inverted: false - "blue_left" : - '@id': blueRightLeft - filename: "calciferRightBlueLeftProfile.csv" - inverted: false - "blue_right" : - '@id': blueRightRight - filename: "calciferRightBlueRightProfile.csv" - inverted: false - "red_center" : - '@id': redRightCenter - filename: "calciferRightRedMidProfile.csv" - inverted: false - "red_left" : - '@id': redRightLeft - filename: "calciferRightRedLeftProfile.csv" - inverted: false - "red_right" : - '@id': redRightRight - filename: "calciferRightRedRightProfile.csv" - inverted: false -allianceSwitch: - '@id': allianceSwitch - ports: [3] -dropGearSwitch: - '@id': dropGearSwitch - ports: [2] -locationDial: - '@id': locationDial - ports: [0, 1] drive: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: '@id': drive @@ -76,7 +18,7 @@ drive: &leftMaster '@id': leftMaster port: 5 - inverted: false + invertInVoltage: false enableBrakeMode: true feetPerRotation: 1.002 currentLimit: 40 @@ -85,15 +27,19 @@ drive: reverseSensor: false reverseOutput: false perGearSettings: - - fwdPeakOutputVoltage: 12 + - &gearSettings + fwdPeakOutputVoltage: 12 fwdNominalOutputVoltage: 0.0 maxSpeed: 11.8 - kP: 0.3 + kP: 0.1 kI: 0.0 - kD: 3.0 - motionProfileP: 1.0 - motionProfileI: 0.0 - motionProfileD: 0.0 + kD: 1.0 + motionProfilePFwd: 1.0 + motionProfileIFwd: 0.0 + motionProfileDFwd: 20.0 + maxAccelFwd: 54 + maxSpeedMPFwd: 15.132 + frictionCompFPSFwd: 1.55 slaves: - '@id': talon1 port: 6 @@ -106,9 +52,13 @@ drive: <<: *leftMaster '@id': rightMaster port: 2 - inverted: false + invertInVoltage: true reverseSensor: true reverseOutput: true + perGearSettings: + - <<: *gearSettings + maxSpeedMPFwd: 13.619 + frictionCompFPSFwd: 1.705 slaves: - '@id': talon3 port: 9 @@ -116,13 +66,6 @@ drive: - '@id': talon5 port: 8 inverted: false - MPHandler: - '@id': driveMPHandler - talons: - - leftMaster - - rightMaster - updaterProcessPeriodSecs: 0.005 - minNumPointsInBtmBuffer: 10 VelScale: 0.9 navX: '@id': driveNavX @@ -131,26 +74,20 @@ pneumatics: org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: '@id': pneumatics nodeID: 15 -logger: - '@id': logger - subsystems: - - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: - drive - loopTimeSecs: 0.02 - eventLogFilename: "/home/lvuser/logs/eventLog-" - telemetryLogFilename: "/home/lvuser/logs/telemetryLog-" oi: org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: '@id': oi gamepad: - '@id': driverGamepad - port: 1 + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': driverGamepad + port: 1 rotThrottle: org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded: &rotThrottle '@id': rotThrottle stick: driverGamepad axis: 0 + smoothingTimeSecs: 0.04 deadband: 0.05 inverted: false fwdThrottle: @@ -185,48 +122,70 @@ defaultDriveCommand: oi: org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: oi -centerAuto: - org.usfirst.frc.team449.robot.commands.general.CommandSequence: - '@id': centerAuto - commandList: - - org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.commands.RunLoadedProfile: - '@id': runCenterWallToPegProfile +nonMPAutoCommand: + org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed: + '@id': nonMPAuto + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + velocity: 1.0 + seconds: 1.5 +autoStartupCommand: + org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: + '@id': startupCommand + commandSet: + - org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.commands.StartCompressor: + '@id': startCompressor + subsystem: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + pneumatics + - org.usfirst.frc.team449.robot.drive.commands.EnableMotors: + '@id': enableMotors + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + - org.usfirst.frc.team449.robot.drive.commands.ResetPosition: + '@id': resetPosition subsystem: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: drive - timeout: 10 - require: true - minRunTimeSecs: 0.1 - - org.usfirst.frc.team449.robot.commands.general.WaitForMillis: - '@id': waitCommand1 - time: 50 - - org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: - '@id': runBackupProfile +teleopStartupCommand: + org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: + startupCommand +startupCommand: + org.usfirst.frc.team449.robot.commands.general.RunRunnables: + '@id': runRunnables + runnables: + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + '@id': noahPoseEstimator + robotDiameter: 2.0833 subsystem: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: drive - left: - '@id': blueLeftCenterReverse - filename: "calciferLeftBlueMidProfile.csv" - inverted: true - right: - '@id': blueRightCenterReverse - filename: "calciferRightBlueMidProfile.csv" - inverted: true - timeout: 10 - minRunTimeSecs: 0.5 - - org.usfirst.frc.team449.robot.commands.general.WaitForMillis: - '@id': waitCommand2 - time: 50 - - org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: - '@id': fwdAgain + absolutePosAngleTolerance: 5 + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + '@id': eliPoseEstimator subsystem: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: drive - left: - blueLeftCenter - right: - blueRightCenter - timeout: 10 - minRunTimeSecs: 0.5 -buttons: \ No newline at end of file + absolutePosAngleTolerance: 5 +logger: + '@id': logger + subsystems: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster: + drive + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + noahPoseEstimator + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + eliPoseEstimator + loopTimeSecs: 0.02 + eventLogFilename: "/home/lvuser/logs/eventLog-" + telemetryLogFilename: "/home/lvuser/logs/telemetryLog-" +updater: + org.usfirst.frc.team449.robot.other.Updater: + '@id': updater + updatables: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi \ No newline at end of file diff --git a/RoboRIO/src/main/resources/calciferLeftBlueBackupProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueBackupProfile.csv index e54cb1bb..9e49c7f5 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueBackupProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueBackupProfile.csv @@ -1,55 +1,49 @@ -54 -3.6998202195815923E-4, 0.014799280878326368, 0.05, -0.0016598585659637298, 0.02579753088011141, 0.05, -0.00456453440812901, 0.058093516843305604, 0.05, -0.009736780007313877, 0.10344491198369735, 0.05, -0.017839832946141745, 0.16206105877655733, 0.05, -0.029553962908322517, 0.23428259924361547, 0.05, -0.04558452438091224, 0.32061122945179443, 0.05, -0.06667136828171022, 0.4217368780159597, 0.05, -0.09359946125912086, 0.5385618595482127, 0.05, -0.1272105710811522, 0.6722221964406268, 0.05, -0.16807301705612493, 0.8172489194994549, 0.05, -0.21646743551455633, 0.9678883691686276, 0.05, -0.2727166853993793, 1.1249849976964599, 0.05, -0.337186048202079, 1.2893872560539932, 0.05, -0.41028513081610507, 1.4619816522805213, 0.05, -0.49247214172896103, 1.6437402182571188, 0.05, -0.5842612721242723, 1.8357826079062252, 0.05, -0.6858366380214413, 2.0315073179433822, 0.05, -0.7970122085133569, 2.22351140983831, 0.05, -0.9176009722860492, 2.4117752754538464, 0.05, -1.0474140419043465, 2.596261392365944, 0.05, -1.1862558344826994, 2.7768358515670593, 0.05, -1.3339112137862812, 2.9531075860716363, 0.05, -1.490119631756835, 3.124168359411078, 0.05, -1.65453101456359, 3.2882276561350996, 0.05, -1.8266394777861632, 3.44216926445146, 0.05, -2.005573645763164, 3.578683359540009, 0.05, -2.190102794812028, 3.6905829809772848, 0.05, -2.378684170630626, 3.771627516371953, 0.05, -2.5693176875725445, 3.81267033883837, 0.05, -2.759599402518523, 3.8056342989195713, 0.05, -2.946872367560439, 3.7454593008383132, 0.05, -3.1284463650146055, 3.6314799490833294, 0.05, -3.3018235617964797, 3.4675439356374826, 0.05, -3.464863868073202, 3.260806125534449, 0.05, -3.6158542077459597, 3.0198067934551562, 0.05, -3.7536192744114567, 2.755301333309943, 0.05, -3.8778743299406693, 2.4851011105842495, 0.05, -3.988955314752372, 2.221619696234056, 0.05, -4.0872719633166055, 1.966332971284676, 0.05, -4.17324899764151, 1.719540686498095, 0.05, -4.247289766422093, 1.4808153756116704, 0.05, -4.3097559164647645, 1.2493230008534204, 0.05, -4.36107902606379, 1.0264621919805206, 0.05, -4.402163348463961, 0.8216864480034127, 0.05, -4.434254593872503, 0.6418249081708596, 0.05, -4.4585365423441035, 0.4856389694319977, 0.05, -4.476145765944183, 0.352184472001578, 0.05, -4.488184183890034, 0.2407683589170284, 0.05, -4.495729469015408, 0.15090570250747054, 0.05, -4.4998434292031835, 0.08227920375551274, 0.05, -4.501578501017331, 0.03470143628294848, 0.05, -4.501982459636722, 0.008079172387830838, 0.05, -4.501982459636722, 0.0, 0.05, +48 +5.227250022608844E-4, 0.020909000090435375, 0.41818000180870746, 0.05 +0.0023454064609125854, 0.03645362917303402, 0.31089258165197287, 0.05 +0.006451335591911353, 0.08211858261997534, 0.9132990689388265, 0.05 +0.013767472257941222, 0.14632273332059736, 1.2840830140124404, 0.05 +0.025241613574952037, 0.2294828263402163, 1.6632018603923786, 0.05 +0.0418553796467967, 0.33227532143689326, 2.055849901933539, 0.05 +0.06464003174297048, 0.45569304192347565, 2.468354409731648, 0.05 +0.09469480172644233, 0.601095399669437, 2.9080471549192275, 0.05 +0.1332074081600263, 0.7702521286716791, 3.383134580044842, 0.05 +0.18147657729001396, 0.965383382599753, 3.902625078561477, 0.05 +0.2404406855302663, 1.1792821648050467, 4.277975644105873, 0.05 +0.31065069171082, 1.4042001236110742, 4.49835917612055, 0.05 +0.3927437715777452, 1.6418615973385038, 4.753229474548593, 0.05 +0.4874499975425362, 1.8941245192958196, 5.045258439146316, 0.05 +0.5950581139051417, 2.1521623272521113, 5.160756159125834, 0.05 +0.7153540535348383, 2.40591879259393, 5.07512930683637, 0.05 +0.8481273667100422, 2.655466263504078, 4.990949418202968, 0.05 +0.9931735331474119, 2.900923328747392, 4.909141304866278, 0.05 +1.1502924337050309, 3.1423780111523802, 4.829093648099763, 0.05 +1.3192736926504234, 3.379625178907851, 4.744943355109417, 0.05 +1.4998565316137857, 3.6116567792672476, 4.64063200718793, 0.05 +1.6916494090923582, 3.835857549571447, 4.484015406083985, 0.05 +1.8939964852865554, 4.0469415238839455, 4.221679486249972, 0.05 +2.1050265019648475, 4.220600333565846, 3.4731761936380146, 0.05 +2.3220908512364353, 4.341286985431754, 2.41373303731816, 0.05 +2.542464445259929, 4.407471880469876, 1.3236979007624328, 0.05 +2.762688113645886, 4.404473367719135, -0.05997025501482511, 0.05 +2.9788317905830777, 4.322873538743837, -1.6319965795059588, 0.05 +3.1869227096726442, 4.161818381791327, -3.2211031390501965, 0.05 +3.3833823557902156, 3.929192922351427, -4.652509188798, 0.05 +3.565309805743528, 3.638548999066251, -5.812878465703513, 0.05 +3.7305454088039185, 3.304712061207814, -6.6767387571687475, 0.05 +3.8775596078692334, 2.9402839813062984, -7.288561598030308, 0.05 +4.0060475444395145, 2.569758731405628, -7.410504998013412, 0.05 +4.116681535994646, 2.212679831102628, -7.141578006059994, 0.05 +4.2101534706927835, 1.8694386939627594, -6.864822742797374, 0.05 +4.287094483589678, 1.538820257937898, -6.612368720497228, 0.05 +4.348789153451391, 1.2338933972342632, -6.098537214072697, 0.05 +4.397143368340726, 0.9670842977866958, -5.336181988951347, 0.05 +4.433938830184443, 0.7359092368743492, -4.623501218246933, 0.05 +4.46085518758187, 0.5383271479485249, -3.951641778516486, 0.05 +4.479496530208541, 0.3728268525334408, -3.3100059083016817, 0.05 +4.491413605561772, 0.23834150706461005, -2.6897069093766146, 0.05 +4.4981217735861785, 0.13416336048813954, -2.08356293152941, 0.05 +4.501114983083293, 0.05986418994229283, -1.4859834109169339, 0.05 +4.501876056532617, 0.015221468986477088, -0.8928544191163148, 0.05 +4.501883477123802, 1.4841182369525153E-4, -0.3014611432556367, 0.05 +4.501883477123802, 0.0, -0.0029682364739050306, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueBoilerToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueBoilerToLoadingProfile.csv index b0034d97..6763d63a 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueBoilerToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueBoilerToLoadingProfile.csv @@ -1,148 +1,152 @@ -147 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002777777777777774, 0.04444444444444436, 0.05, -0.007777777777777759, 0.0999999999999997, 0.05, -0.016666666666666625, 0.1777777777777773, 0.05, -0.03055555555555596, 0.27777777777778667, 0.05, -0.05055555555555677, 0.40000000000001623, 0.05, -0.07777777777778011, 0.5444444444444668, 0.05, -0.1133333333333371, 0.7111111111111398, 0.05, -0.1583333333333382, 0.9000000000000221, 0.05, -0.21388888888887678, 1.1111111111107712, 0.05, -0.280555555555523, 1.3333333333329238, 0.05, -0.3583333333333088, 1.5555555555557166, 0.05, -0.4472222222222322, 1.7777777777784676, 0.05, -0.5472222222222709, 2.0000000000007745, 0.05, -0.6583333333333788, 2.222222222222159, 0.05, -0.780555555555479, 2.444444444442002, 0.05, -0.9138888888886788, 2.666666666663997, 0.05, -1.0583333333329787, 2.8888888888859965, 0.05, -1.2138888888883792, 3.111111111108009, 0.05, -1.380555555554879, 3.3333333333299953, 0.05, -1.558333333332479, 3.555555555551999, 0.05, -1.7472222222211788, 3.7777777777739985, 0.05, -1.947222222220979, 3.9999999999960023, 0.05, -2.1583333333318793, 4.222222222218002, 0.05, -2.380555555553879, 4.444444444439997, 0.05, -2.6138888888876117, 4.666666666674653, 0.05, -2.8583333333331686, 4.888888888911138, 0.05, -3.113333333334329, 5.100000000023206, 0.05, -3.3777777777799773, 5.288888888912968, 0.05, -3.6505555555589964, 5.45555555558038, 0.05, -3.9305555555602707, 5.600000000025487, 0.05, -4.216666666672683, 5.722222222248261, 0.05, -4.507777777785119, 5.822222222248712, 0.05, -4.802777777786462, 5.900000000026857, 0.05, -5.109691288422086, 6.138270212712478, 0.05, -5.438037762698388, 6.566929485526026, 0.05, -5.767930011799243, 6.5978449820171035, 0.05, -6.098718768426794, 6.6157751325510095, 0.05, -6.430348540827206, 6.632595448008228, 0.05, -6.762748603828744, 6.648001260030763, 0.05, -7.095832702508137, 6.661681973587852, 0.05, -7.429499319929359, 6.673332348424453, 0.05, -7.763632583382258, 6.682665269057987, 0.05, -8.098103845780841, 6.68942524797167, 0.05, -8.43277392990415, 6.693401682466176, 0.05, -8.767495950872304, 6.6944404193630875, 0.05, -9.102118590767137, 6.692452797896666, 0.05, -9.436489641562908, 6.6874210159153895, 0.05, -9.770459598695169, 6.679399142645209, 0.05, -10.103885095307637, 6.668509932249368, 0.05, -10.436631967462757, 6.654937443102387, 0.05, -10.768577795245939, 6.638916555663625, 0.05, -11.099613807119956, 6.620720237480353, 0.05, -11.42964610266206, 6.60064591084206, 0.05, -11.75859620194768, 6.579001985712398, 0.05, -12.086400980543967, 6.556095571925729, 0.05, -12.4130120824346, 6.53222203781264, 0.05, -12.738394922914196, 6.507656809591927, 0.05, -13.062527399361414, 6.482649528944376, 0.05, -13.385398421075324, 6.457420434278214, 0.05, -13.707006357564731, 6.432158729788131, 0.05, -14.027357484414644, 6.407022536998255, 0.05, -14.346464488888763, 6.382140089482374, 0.05, -14.664345077942041, 6.357611781065554, 0.05, -14.981020714664968, 6.3335127344585445, 0.05, -15.296515497306428, 6.30989565282922, 0.05, -15.610855183840968, 6.2867937306907855, 0.05, -15.924066356260047, 6.2642234483815935, 0.05, -16.23617571788165, 6.242187232432039, 0.05, -16.547209508598357, 6.220675814334117, 0.05, -16.85719302572516, 6.199670342536083, 0.05, -17.16615023696744, 6.179144224845623, 0.05, -17.474103470391487, 6.159064668480979, 0.05, -17.781073170209265, 6.139393996355529, 0.05, -18.087077706596318, 6.120090727741092, 0.05, -18.392133229138544, 6.101110450844518, 0.05, -18.696253556188985, 6.082406541008833, 0.05, -18.999450092309992, 6.063930722420127, 0.05, -19.301731768700094, 6.045633527802033, 0.05, -19.60310500083224, 6.027464642642939, 0.05, -19.903573660919726, 6.0093732017497, 0.05, -20.203139062093445, 5.991308023474417, 0.05, -20.50179995304164, 5.973217818963887, 0.05, -20.799552522640894, 5.955051391985055, 0.05, -21.096390414827813, 5.936757843738337, 0.05, -21.392304755517536, 5.9182868137944995, 0.05, -21.687284193604974, 5.899588761748787, 0.05, -21.981314959749533, 5.880615322891183, 0.05, -22.27438094731102, 5.861319751229736, 0.05, -22.56646382171067, 5.841657487993027, 0.05, -22.857543164765072, 5.8215868610880515, 0.05, -23.147596663232637, 5.801069969351255, 0.05, -23.4366003499282, 5.78007373391122, 0.05, -23.724528911072778, 5.758571222891586, 0.05, -24.011356070621225, 5.736543190968942, 0.05, -24.297055064778878, 5.713979883153015, 0.05, -24.581599223276825, 5.690883169958972, 0.05, -24.864962667591406, 5.667268886291642, 0.05, -25.147121142492182, 5.643169498015523, 0.05, -25.42805298652962, 5.618636880748791, 0.05, -25.70774024961429, 5.593745261693345, 0.05, -25.986169952895846, 5.568594065631148, 0.05, -26.263335478643175, 5.543310514946557, 0.05, -26.539238064528302, 5.518051717702541, 0.05, -26.813888359624325, 5.493005901920458, 0.05, -27.087307981720354, 5.468392441920541, 0.05, -27.359530995802412, 5.44446028164116, 0.05, -27.630605216357853, 5.4214844111088185, 0.05, -27.900593221234274, 5.399760097528383, 0.05, -28.169259623355803, 5.373328042430556, 0.05, -28.43589291466694, 5.332665826222767, 0.05, -28.69962191943615, 5.2745800953842314, 0.05, -28.95959497592623, 5.199461129801556, 0.05, -29.214972562757175, 5.107551736618892, 0.05, -29.46491918135902, 4.998932372036852, 0.05, -29.70859518001957, 4.873519973211082, 0.05, -29.945149211737505, 4.731080634358627, 0.05, -30.173711932695436, 4.571254419158657, 0.05, -30.393391369416825, 4.393588734427746, 0.05, -30.60358021757754, 4.203776963214308, 0.05, -30.804138884554213, 4.011173339533435, 0.05, -30.995089298657316, 3.8190082820620366, 0.05, -31.176436529903924, 3.626944624932194, 0.05, -31.34817202186585, 3.434709839238516, 0.05, -31.51027660423133, 3.2420916473095795, 0.05, -31.66272321459987, 3.048932207370788, 0.05, -31.80547927028284, 2.855121113659479, 0.05, -31.938508698008462, 2.6605885545124432, 0.05, -32.061773616443745, 2.465298368705634, 0.05, -32.175235715969585, 2.2692419905168437, 0.05, -32.27885736386594, 2.0724329579270653, 0.05, -32.372602475677915, 1.8749022362394747, 0.05, -32.45643719097551, 1.676694305951771, 0.05, -32.53033038763155, 1.477863933120846, 0.05, -32.59425406964583, 1.2784736402855406, 0.05, -32.64818364952629, 1.0785915976091716, 0.05, -32.69241490601172, 0.8846251297086539, 0.05, -32.727750806206465, 0.70671800389497, 0.05, -32.75518507263692, 0.54868532860902, 0.05, -32.775715513227446, 0.4106088118105775, 0.05, -32.79034307244701, 0.292551184391216, 0.05, -32.80007100732749, 0.19455869760961378, 0.05, -32.80590417667593, 0.11666338696876882, 0.05, -32.80884846353619, 0.05888573720518136, 0.05, -32.809910326155766, 0.02123725239157871, 0.05, -32.81009648352595, 0.0037231474036812477, 0.05, -32.81009648352595, 0.0, 0.05, +151 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002717391304347822, 0.04347826086956514, 0.4347826086956506, 0.05 +0.007608695652173897, 0.09782608695652148, 1.0869565217391268, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.029891304347826463, 0.27173913043479087, 1.956521739130609, 0.05 +0.04945652173913161, 0.391304347826103, 2.391304347826243, 0.05 +0.07608695652174138, 0.5326086956521955, 2.8260869565218494, 0.05 +0.11086956521739495, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783155, 0.8804347826087319, 3.695652173913211, 0.05 +0.20923913043477188, 1.0869565217388066, 4.130434782601495, 0.05 +0.27445652173909973, 1.304347826086557, 4.347826086955009, 0.05 +0.350543478260842, 1.5217391304348449, 4.347826086965756, 0.05 +0.4375000000000061, 1.7391304347832826, 4.3478260869687535, 0.05 +0.5353260869565658, 1.956521739131194, 4.347826086958229, 0.05 +0.6440217391304945, 2.1739130434785747, 4.347826086947615, 0.05 +0.7635869565216794, 2.3913043478236973, 4.347826086902451, 0.05 +0.8940217391302444, 2.6086956521713, 4.347826086952056, 0.05 +1.0353260869561902, 2.826086956518914, 4.347826086952278, 0.05 +1.1874999999995164, 3.0434782608665234, 4.347826086952189, 0.05 +1.350543478260223, 3.260869565214133, 4.347826086952189, 0.05 +1.5244565217383097, 3.4782608695617334, 4.347826086952011, 0.05 +1.709239130433777, 3.6956521739093473, 4.347826086952278, 0.05 +1.904891304346625, 3.9130434782569568, 4.347826086952189, 0.05 +2.1108695652159843, 4.119565217387184, 4.130434782604553, 0.05 +2.3260869565201174, 4.304347826082662, 3.695652173909547, 0.05 +2.5494565217375595, 4.467391304348842, 3.2608695653236097, 0.05 +2.779891304347304, 4.608695652194887, 2.8260869569209035, 0.05 +3.016304347826641, 4.7282608695867445, 2.391304347837142, 0.05 +3.257608695653826, 4.826086956543696, 1.9565217391390277, 0.05 +3.5027173913071152, 4.902173913065786, 1.5217391304418015, 0.05 +3.7505434782647646, 4.956521739152988, 1.0869565217440424, 0.05 +4.000000000005031, 4.989130434805329, 0.6521739130468163, 0.05 +4.2500000000061675, 5.000000000022737, 0.217391304348169, 0.05 +4.500000000007306, 5.000000000022773, 7.105427357601002E-13, 0.05 +4.750000000008443, 5.000000000022737, -7.105427357601002E-13, 0.05 +5.000000000009582, 5.000000000022773, 7.105427357601002E-13, 0.05 +5.276969549562218, 5.539390991052737, 10.787819820599278, 0.05 +5.555614393286303, 5.572896874481703, 0.6701176685793264, 0.05 +5.835626077238715, 5.600233679048246, 0.5467360913308639, 0.05 +6.117024137326496, 5.627961201755602, 0.5545504541471225, 0.05 +6.399813044312992, 5.655778139729935, 0.5563387594866498, 0.05 +6.683978844427567, 5.683316002291488, 0.5507572512310688, 0.05 +6.9694858004734055, 5.710139120916782, 0.536462372505877, 0.05 +7.256273251727427, 5.735749025080415, 0.5121980832726614, 0.05 +7.544253008105114, 5.759595127553745, 0.47692204946660155, 0.05 +7.8333076334011125, 5.7810925059199665, 0.4299475673244224, 0.05 +8.123289964884789, 5.799646629673514, 0.37108247507095626, 0.05 +8.414024189225538, 5.8146844868149925, 0.3007571428295641, 0.05 +8.705308664811087, 5.825689511710981, 0.22010049791976627, 0.05 +8.996920527222738, 5.832237248233031, 0.13095473044099748, 0.05 +9.288621898830993, 5.834027432165106, 0.03580367864151057, 0.05 +9.580167303239445, 5.830908088169064, -0.062386879920843796, 0.05 +9.871311721621291, 5.82288836763693, -0.160394410642688, 0.05 +10.161818617714868, 5.810137921871554, -0.25500891530750636, 0.05 +10.451467267598884, 5.792972997680319, -0.3432984838247144, 0.05 +10.74005883215077, 5.771831291037734, -0.42283413285169047, 0.05 +11.027420791285063, 5.747239182685841, -0.4918421670378592, 0.05 +11.313409574984245, 5.719775673983648, -0.5492701740438655, 0.05 +11.597911435945631, 5.6900372192277375, -0.5947690951182061, 0.05 +11.880841775782086, 5.658606796729072, -0.6286084499733136, 0.05 +12.162143244301902, 5.6260293703963, -0.6515485266554322, 0.05 +12.441782973496798, 5.592794583897911, -0.6646957299677858, 0.05 +12.719749301343775, 5.559326556939552, -0.6693605391671831, 0.05 +12.99604829071052, 5.525979787334925, -0.6669353920925403, 0.05 +13.270700286518585, 5.4930399161612815, -0.6587974234728655, 0.05 +13.543736682863043, 5.4607279268891835, -0.6462397854419599, 0.05 +13.815197009397552, 5.4292065306901645, -0.6304279239803812, 0.05 +14.085126388030284, 5.3985875726546295, -0.6123791607106988, 0.05 +14.353573378091209, 5.368939801218498, -0.5929554287226324, 0.05 +14.620588193909573, 5.340296316367255, -0.5728696970248492, 0.05 +14.88622126363381, 5.312661394484762, -0.5526984376498767, 0.05 +15.150522089775654, 5.286016522836865, -0.5328974329579239, 0.05 +15.41353836722997, 5.260325549086332, -0.5138194750106706, 0.05 +15.675315315415618, 5.2355389637129806, -0.49573170746702644, 0.05 +15.935895186657792, 5.211597424843459, -0.47883077739042434, 0.05 +16.19531691231783, 5.188434513200733, -0.4632582328545354, 0.05 +16.45361585876103, 5.165978928863997, -0.4491116867347067, 0.05 +16.71082366545245, 5.144156133828349, -0.43645590071296425, 0.05 +16.96696814505646, 5.122889592080235, -0.4253308349622742, 0.05 +17.22207322708511, 5.102101640573051, -0.41575903014368976, 0.05 +17.476158932030717, 5.081714098912083, -0.40775083321936023, 0.05 +17.729241364503117, 5.061648649448025, -0.401308989281155, 0.05 +17.98133271674417, 5.041827044821057, -0.3964320925393672, 0.05 +18.23244127694146, 5.022171203945865, -0.393116817503838, 0.05 +18.482571437265072, 5.00260320647221, -0.3913599494731024, 0.05 +18.731723698727812, 4.983045229254783, -0.39115954434853606, 0.05 +18.979894671616364, 4.963419457771025, -0.3925154296751643, 0.05 +19.227077071097682, 4.94364798962637, -0.3954293628931005, 0.05 +19.47325970925166, 4.92365276307954, -0.39990453093659895, 0.05 +19.718427486067895, 4.903355536324668, -0.40594453509744, 0.05 +19.962561383353886, 4.88267794571982, -0.413551812096955, 0.05 +20.20563846734464, 4.8615416798151125, -0.42272531809414815, 0.05 +20.447631908341734, 4.839868819941815, -0.4334571974659518, 0.05 +20.688511026834124, 4.817582369847813, -0.4457290018800464, 0.05 +20.928241379354144, 4.7946070504003835, -0.45950638894858287, 0.05 +21.166784901708922, 4.770870447095585, -0.47473206609597085, 0.05 +21.40410012798889, 4.74630452559934, -0.49131842992489183, 0.05 +21.64014251152143, 4.720847670650741, -0.5091370989719834, 0.05 +21.874864876215497, 4.694447293881386, -0.5280075353871005, 0.05 +22.10821803382322, 4.667063152154493, -0.5476828345378593, 0.05 +22.340151603832872, 4.638671400193, -0.5678350392298626, 0.05 +22.570615080914905, 4.60926954164066, -0.5880371710468069, 0.05 +22.799559192308042, 4.57888222786276, -0.6077462755579965, 0.05 +23.02693758649129, 4.547567883664967, -0.62628688395586, 0.05 +23.252708889805, 4.5154260662741725, -0.6428363478158872, 0.05 +23.47683914889965, 4.482605181893016, -0.6564176876231365, 0.05 +23.699304652954755, 4.449310081102087, -0.6659020158185669, 0.05 +23.920095096584227, 4.415808872589413, -0.6700241702534804, 0.05 +24.139216986596235, 4.3824378002401625, -0.667421446985017, 0.05 +24.35669714198429, 4.349603107761105, -0.6566938495811492, 0.05 +24.572586061177986, 4.317778383873894, -0.6364944777442183, 0.05 +24.78696086557763, 4.28749608799287, -0.6056459176204854, 0.05 +24.999927474906865, 4.2593321865847065, -0.5632780281632677, 0.05 +25.211621647885902, 4.23388345958075, -0.5089745400791301, 0.05 +25.422208550904536, 4.211738060372636, -0.44290798416227517, 0.05 +25.63188060644297, 4.1934411107686556, -0.365938992079613, 0.05 +25.840853526029967, 4.179458391739967, -0.27965438057377057, 0.05 +26.04902771912142, 4.163483861829018, -0.31949059821897663, 0.05 +26.25586210609647, 4.1366877395009665, -0.5359224465610346, 0.05 +26.460693748963507, 4.096632857340768, -0.801097643203974, 0.05 +26.662840454053086, 4.042934101791582, -1.0739751109837137, 0.05 +26.86158536744313, 3.9748982678009046, -1.3607166798135495, 0.05 +27.056165588098246, 3.89160441310228, -1.665877093972492, 0.05 +27.245765548734365, 3.791999212722393, -1.992104007597737, 0.05 +27.429515147552184, 3.6749919763563685, -2.3401447273204923, 0.05 +27.606491977696376, 3.5395366028838557, -2.709107469450256, 0.05 +27.775726648042628, 3.384693406925039, -3.096863919176336, 0.05 +27.93655322556685, 3.2165315504844516, -3.363237128811747, 0.05 +28.088749298251194, 3.043921453686873, -3.452201935951571, 0.05 +28.23220733211291, 2.869160677234339, -3.495215529050677, 0.05 +28.366817470861587, 2.6922027749735715, -3.5391580452153537, 0.05 +28.492471452656943, 2.5130796359071526, -3.5824627813283794, 0.05 +28.60906537670173, 2.331878480895714, -3.6240231002287704, 0.05 +28.716501574243, 2.1487239508254294, -3.663090601405692, 0.05 +28.814689797811837, 1.9637644713767632, -3.699189588973324, 0.05 +28.90354790571162, 1.7771621579956445, -3.7320462676223753, 0.05 +28.983002203179804, 1.5890859493637224, -3.761524172638442, 0.05 +29.052987538562114, 1.3997067076461704, -3.7875848343510388, 0.05 +29.11344724230408, 1.2091940748393113, -3.810252656137183, 0.05 +29.16433298625096, 1.017714878937644, -3.8295839180333457, 0.05 +29.205960454207485, 0.8325493591304731, -3.7033103961434177, 0.05 +29.23913903826959, 0.6635716812421192, -3.3795535577670788, 0.05 +29.264815943026786, 0.5135380951438641, -3.0006717219651025, 0.05 +29.28394605316524, 0.3826022027691113, -2.6187178474950557, 0.05 +29.297490032114414, 0.27087957898344417, -2.234452475713342, 0.05 +29.306412721933494, 0.17845379638163178, -1.8485156520362478, 0.05 +29.31168181809099, 0.1053819231498698, -1.4614374646352395, 0.05 +29.314266806985547, 0.05169977789118507, -1.0736429051736944, 0.05 +29.315138159895625, 0.017427058201585358, -0.6854543937919944, 0.05 +29.315266777758186, 0.002572357251218391, -0.29709401900733934, 0.05 +29.315266777758186, 0.0, -0.05144714502436782, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueLeftProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueLeftProfile.csv index 074e6f98..2787cda6 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueLeftProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueLeftProfile.csv @@ -1,90 +1,78 @@ -89 -3.676470588235294E-4, 0.014705882352941176, 0.05, -0.0019563486445236342, 0.0317740317140021, 0.05, -0.005531005239688499, 0.0714931319032973, 0.05, -0.011886217108935676, 0.12710423738494353, 0.05, -0.021816919982575272, 0.1986140574727919, 0.05, -0.036118598905930416, 0.2860335784671028, 0.05, -0.055587557513489635, 0.38937917215118445, 0.05, -0.0810212422155988, 0.5086736940421831, 0.05, -0.1132186230636419, 0.6439476169608621, 0.05, -0.1529806331254745, 0.7952402012366518, 0.05, -0.2007128183978204, 0.9546437054469178, 0.05, -0.2564249390895163, 1.114242413833918, 0.05, -0.32012843301569344, 1.2740698785235427, 0.05, -0.39183643410013425, 1.4341600216888155, 0.05, -0.4715637901353261, 1.594547120703838, 0.05, -0.5593270770528956, 1.7552657383513894, 0.05, -0.6551446087320479, 1.9163506335830456, 0.05, -0.7590364385271953, 2.0778365959029457, 0.05, -0.8710243494581498, 2.2397582186190887, 0.05, -0.9911318289135421, 2.402149589107847, 0.05, -1.1193840227439371, 2.565043876607899, 0.05, -1.2558076636579512, 2.72847281828028, 0.05, -1.400430965459529, 2.8924660360315593, 0.05, -1.55328347678674, 3.0570502265442188, 0.05, -1.7143958835453905, 3.22224813517301, 0.05, -1.883799750527969, 3.38807733965157, 0.05, -2.0615271902885435, 3.5545487952114834, 0.05, -2.2476104469510765, 3.721665133250663, 0.05, -2.4420813814600715, 3.8894186901799026, 0.05, -2.6449708463447754, 4.057789297694076, 0.05, -2.856307937456978, 4.226741822244052, 0.05, -3.0761191140403974, 4.396223531668385, 0.05, -3.304427181566854, 4.566161350529131, 0.05, -3.541250138828623, 4.736459145235378, 0.05, -3.7861907113576816, 4.898811450581174, 0.05, -4.038432231757844, 5.044830408003254, 0.05, -4.297145428192242, 5.174263928687955, 0.05, -4.561488305347728, 5.286857543109727, 0.05, -4.830606545889282, 5.382364810831076, 0.05, -5.103634472341676, 5.460558529047887, 0.05, -5.379696572830811, 5.521242009782696, 0.05, -5.657909550303767, 5.564259549459118, 0.05, -5.937384809861801, 5.589505191160685, 0.05, -6.217231257419917, 5.596928951162324, 0.05, -6.496611728565865, 5.587609422918958, 0.05, -6.774692288919117, 5.561611207065034, 0.05, -7.050591477657114, 5.5179837747599345, 0.05, -7.3234362480704664, 5.456895408267055, 0.05, -7.5923639380550565, 5.378553799691794, 0.05, -7.856523710443304, 5.2831954477649585, 0.05, -8.115077431238321, 5.1710744159003434, 0.05, -8.367199996495664, 5.042451305146862, 0.05, -8.612079153587707, 4.897583141840878, 0.05, -8.848914887798186, 4.736714684209583, 0.05, -9.077271250258898, 4.567127249214249, 0.05, -9.297124717349755, 4.3970693418171285, 0.05, -9.50850788947855, 4.227663442575896, 0.05, -9.711455524968777, 4.058952709804564, 0.05, -9.906003652649606, 3.8909625536165584, 0.05, -10.09218883368858, 3.723703620779471, 0.05, -10.270047559166166, 3.557174509551713, 0.05, -10.439615766819168, 3.3913641530600462, 0.05, -10.600928460673495, 3.2262538770865414, 0.05, -10.754019418974902, 3.0618191660281378, 0.05, -10.898920974675386, 2.898031114009665, 0.05, -11.035663857008382, 2.734857646659926, 0.05, -11.164277081546695, 2.5722644907662677, 0.05, -11.284787879559751, 2.4102159602611146, 0.05, -11.39722165821806, 2.2486755731661607, 0.05, -11.501601984445381, 2.0876065245464295, 0.05, -11.597950586584735, 1.9269720427870913, 0.05, -11.686287369128932, 1.7667356508839382, 0.05, -11.766630436362513, 1.6068613446716367, 0.05, -11.838996121857157, 1.4473137098928734, 0.05, -11.903399021150364, 1.2880579858641434, 0.05, -11.95985202554784, 1.1290600879495443, 0.05, -12.008366355434987, 0.970286597742907, 0.05, -12.048951591467032, 0.8117047206409213, 0.05, -12.081959680495963, 0.6601617805786248, 0.05, -12.108136006574819, 0.5235265215771004, 0.05, -12.128275456626389, 0.40278900103137794, 0.05, -12.143171406429593, 0.29791899606407474, 0.05, -12.153616093519641, 0.20889374180097994, 0.05, -12.160400935655595, 0.1356968427190742, 0.05, -12.164316794278367, 0.07831717245544526, 0.05, -12.166154186494639, 0.03674784432544433, 0.05, -12.16670344449413, 0.010985159989833987, 0.05, -12.166754824102762, 0.001027592172618803, 0.05, -12.166754824102762, 0.0, 0.05, +77 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002879763320123809, 0.04672570118508487, 0.4997314150060453, 0.05 +0.008136571694489194, 0.1051361674873077, 1.1682093260444564, 0.05 +0.017482579183684517, 0.18692014978390648, 1.6356796459319756, 0.05 +0.032087179169735816, 0.292091999721026, 2.1034369987423904, 0.05 +0.053120942354197176, 0.4206752636892271, 2.5716652793640216, 0.05 +0.08175619666960292, 0.5727050863081148, 3.0405964523777538, 0.05 +0.1191677313710831, 0.7482306940296035, 3.5105121544297746, 0.05 +0.16653363045241873, 0.9473179816267127, 3.981745751942183, 0.05 +0.22503624445150686, 1.1700522799817623, 4.454685967100993, 0.05 +0.2952777876984303, 1.404830864938469, 4.695571699134136, 0.05 +0.3772795311119139, 1.640034868269672, 4.704080066624057, 0.05 +0.471066546394621, 1.8757403056541404, 4.7141087476893695, 0.05 +0.5766678080400616, 2.1120252329088114, 4.72569854509342, 0.05 +0.6941162962168161, 2.3489697635350915, 4.738890612525601, 0.05 +0.8234490940685816, 2.586655957035309, 4.753723870004354, 0.05 +0.9647074680538872, 2.825167479706112, 4.77023045341606, 0.05 +1.1179369188374673, 3.0645890156716025, 4.788430719309806, 0.05 +1.283187185593966, 3.305005335129976, 4.808326389167474, 0.05 +1.460512182088941, 3.546499929899501, 4.829891895390492, 0.05 +1.649969836461184, 3.789153087444855, 4.8530631509070865, 0.05 +1.8516218010473748, 4.033039291723817, 4.87772408557924, 0.05 +2.0655329891562615, 4.278223762177733, 4.903689409078318, 0.05 +2.2911749473656875, 4.512839164188518, 4.692308040215707, 0.05 +2.527418691338955, 4.724874879465344, 4.24071430553651, 0.05 +2.773125095898926, 4.914128091199423, 3.785064234681581, 0.05 +3.027142832119376, 5.080354724409004, 3.324532664191615, 0.05 +3.2883064993733244, 5.2232733450789635, 2.858372413399195, 0.05 +3.5554350740118967, 5.342571492771449, 2.3859629538497096, 0.05 +3.8273308069399836, 5.437914658561734, 1.9068633158057047, 0.05 +4.10277870263442, 5.508957913888725, 1.4208651065398215, 0.05 +4.38054669601642, 5.5553598676400116, 0.9280390750257261, 0.05 +4.659386606362977, 5.57679820693113, 0.42876678582237204, 0.05 +4.938643351154318, 5.585134895826821, 0.16673377791381228, 0.05 +5.21826105266993, 5.592354030312241, 0.1443826897084044, 0.05 +5.498178967497802, 5.598358296557452, 0.12008532490421331, 0.05 +5.778332155928365, 5.603063768611266, 0.09410944107628438, 0.05 +6.058652293836246, 5.606402758157618, 0.06677979092703623, 0.05 +6.339068604819993, 5.608326219674941, 0.03846923034647176, 0.05 +6.619508882138948, 5.608805546379091, 0.009586534082988152, 0.05 +6.8999005641244775, 5.607833639710583, -0.019438133370162092, 0.05 +7.1801718229383305, 5.605425176277064, -0.04816926867036386, 0.05 +7.460252625700508, 5.601616055243548, -0.076182420670321, 0.05 +7.7397113893514415, 5.589175273018667, -0.24881564449762195, 0.05 +8.017514851729342, 5.55606924755801, -0.6621205092131532, 0.05 +8.29239729373325, 5.497648840078162, -1.16840814959696, 0.05 +8.56310723238516, 5.414198773038188, -1.669001340799472, 0.05 +8.828409242256509, 5.30604019742695, -2.163171512224764, 0.05 +9.0870849177965, 5.173513510799792, -2.6505337325431633, 0.05 +9.337933005590022, 5.016961755870458, -3.131035098586672, 0.05 +9.579768794049462, 4.836715769188793, -3.6049197336332917, 0.05 +9.81142288364969, 4.633081792004551, -4.072679543684856, 0.05 +10.031739479286287, 4.406331912731927, -4.534997585452469, 0.05 +10.239932533406417, 4.163861082402603, -4.849416606586487, 0.05 +10.435819550241012, 3.9177403366919155, -4.922414914213746, 0.05 +10.619457814071266, 3.67276527660509, -4.899501201736509, 0.05 +10.79090299185517, 3.428903555678054, -4.8772344185407235, 0.05 +10.950208356695741, 3.186107296811436, -4.855925177332354, 0.05 +11.097424222944827, 2.944317324981727, -4.835799436594179, 0.05 +11.23259754999735, 2.7034665410504366, -4.817015678625811, 0.05 +11.35577167783736, 2.463482556800222, -4.799679685004294, 0.05 +11.466986162637035, 2.224289695993481, -4.783857216134821, 0.05 +11.566276687436632, 1.985810495991942, -4.769584000030775, 0.05 +11.653675026366702, 1.7479667786013888, -4.756874347811064, 0.05 +11.729209045494542, 1.5106803825568131, -4.745727920891514, 0.05 +11.792902727803845, 1.273873646186077, -4.736134727414725, 0.05 +11.845129339363467, 1.044532231192431, -4.586828299872918, 0.05 +11.886846859373858, 0.834350400207799, -4.203636619692639, 0.05 +11.919244657983475, 0.6479559721923539, -3.727888560308903, 0.05 +11.943508210864188, 0.48527105761427003, -3.2536982915616774, 0.05 +11.9608200311474, 0.34623640566423725, -2.7806930390006555, 0.05 +11.972360466870374, 0.23080871445947235, -2.3085538240952976, 0.05 +11.97930836965918, 0.1389580557761241, -1.8370131736669648, 0.05 +11.982841635614298, 0.07066531910238105, -1.365854733474861, 0.05 +11.984137622579368, 0.025919739301410113, -0.8949115960194187, 0.05 +11.984373443480766, 0.004716418027978793, -0.4240664254686264, 0.05 +11.984373443480766, 0.0, -0.09432836055957586, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueLoadingToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueLoadingToLoadingProfile.csv index b4964fb7..0ddd9933 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueLoadingToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueLoadingToLoadingProfile.csv @@ -1,130 +1,125 @@ -129 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002870380862297655, 0.04629650613484198, 0.05, -0.00807869996129272, 0.10416638197990132, 0.05, -0.0173378044139253, 0.18518208905265154, 0.05, -0.03180482271891416, 0.28934036609977726, 0.05, -0.05263661512308132, 0.41663584808334325, 0.05, -0.0809896405183791, 0.5670605079059556, 0.05, -0.1180197926130855, 0.7406030418941278, 0.05, -0.16488220517114338, 0.9372482511611577, 0.05, -0.2227310198921128, 1.1569762944193884, 0.05, -0.2921407428106982, 1.3881944583717076, 0.05, -0.3731064129204269, 1.6193134021945739, 0.05, -0.4656221356420951, 1.8503144544333638, 0.05, -0.5696810364710435, 2.081178016578969, 0.05, -0.685275209776766, 2.3118834661144496, 0.05, -0.8123956641787798, 2.542409088040276, 0.05, -0.9510322650425563, 2.77273201727553, 0.05, -1.101173675185074, 3.002828202850353, 0.05, -1.2628072952680809, 3.232672401660138, 0.05, -1.435919204707614, 3.462238188790659, 0.05, -1.6204941050840298, 3.6914980075283177, 0.05, -1.8165152666871291, 3.9204232320619883, 0.05, -2.023964480486758, 4.148984275992575, 0.05, -2.2428220160125023, 4.377150710514893, 0.05, -2.4730665875804863, 4.604891431359681, 0.05, -2.714675329169591, 4.83217483178209, 0.05, -2.9676237796382385, 5.05896900937295, 0.05, -3.231311605374933, 5.273756514733892, 0.05, -3.504564781887297, 5.465063530247279, 0.05, -3.786211502436062, 5.632934410975301, 0.05, -4.075082626088995, 5.777422473058665, 0.05, -4.370012093106151, 5.8985893403431255, 0.05, -4.669837298694824, 5.996504111773452, 0.05, -4.973399417987735, 6.071242385858226, 0.05, -5.279543676159693, 6.122885163439171, 0.05, -5.5871195595990315, 6.151517668786762, 0.05, -5.894980965850023, 6.157228125019841, 0.05, -6.202555606134629, 6.151492805692104, 0.05, -6.509842372954494, 6.145735336397303, 0.05, -6.816840413287636, 6.139960806662836, 0.05, -7.123549104486224, 6.134173823971755, 0.05, -7.429968030719894, 6.128378524673404, 0.05, -7.736096960162958, 6.122578588861279, 0.05, -8.041935822921896, 6.116777255178787, 0.05, -8.347484689883078, 6.110977339223621, 0.05, -8.652743752511427, 6.105181252566966, 0.05, -8.957713303613094, 6.09939102203334, 0.05, -9.262393719178434, 6.093608311306789, 0.05, -9.566785441278538, 6.087834442002087, 0.05, -9.870888961987784, 6.082070414184933, 0.05, -10.174704808499518, 6.076316930234684, 0.05, -10.478233529194428, 6.070574413898202, 0.05, -10.781475680869613, 6.064843033503695, 0.05, -11.08443181699768, 6.059122722561325, 0.05, -11.387102477024731, 6.053413200541023, 0.05, -11.689488176702806, 6.047713993561481, 0.05, -11.99158939942292, 6.042024454402304, 0.05, -12.29340658854198, 6.036343782381182, 0.05, -12.594940140667514, 6.030671042510674, 0.05, -12.896190399892898, 6.02500518450767, 0.05, -13.197157652954944, 6.019345061240933, 0.05, -13.497842125316003, 6.013689447221194, 0.05, -13.798243978139928, 6.008037056478499, 0.05, -14.09836330615925, 6.002386560386435, 0.05, -14.398200136425057, 5.996736605316159, 0.05, -14.697754427935356, 5.991085830205985, 0.05, -14.997026072140043, 5.985432884093735, 0.05, -15.296014894324557, 5.9797764436902945, 0.05, -15.594720655875753, 5.974115231023904, 0.05, -15.893143057439662, 5.968448031278191, 0.05, -16.191281742984973, 5.962773710906186, 0.05, -16.489136304788513, 5.957091236070827, 0.05, -16.786706289324528, 5.951399690720292, 0.05, -17.083991204143135, 5.945698296372163, 0.05, -17.380990525692948, 5.939986430996271, 0.05, -17.67770370814549, 5.934263649050844, 0.05, -17.97413019320771, 5.928529701244369, 0.05, -18.270269421007786, 5.9227845560015195, 0.05, -18.566120841972324, 5.917028419290762, 0.05, -18.861683929795074, 5.911261756454983, 0.05, -19.156958195506483, 5.905485314228153, 0.05, -19.451943202569847, 5.8997001412672585, 0.05, -19.746638583104037, 5.893907610683827, 0.05, -20.04104405518569, 5.888109441633046, 0.05, -20.335159441141382, 5.88230771911385, 0.05, -20.628984686988698, 5.876504916946319, 0.05, -20.922519882778715, 5.870703915800323, 0.05, -21.21576528391917, 5.864908022809064, 0.05, -21.50872133337403, 5.859120989097254, 0.05, -21.801388684621877, 5.853347024956899, 0.05, -22.093768225323355, 5.847590814029584, 0.05, -22.385776696212996, 5.840169417792842, 0.05, -22.67679132989804, 5.820292673700886, 0.05, -22.965736714538497, 5.77890769280913, 0.05, -23.25154183218282, 5.716102352886481, 0.05, -23.533139898722577, 5.631961330795152, 0.05, -23.809468142776115, 5.52656488107076, 0.05, -24.079467525867408, 5.399987661825812, 0.05, -24.342082408667142, 5.252297655994682, 0.05, -24.59626016920215, 5.083555210700122, 0.05, -24.840950780727642, 4.893812230509844, 0.05, -25.07519003427986, 4.6847850710443355, 0.05, -25.29855077607256, 4.467214835853973, 0.05, -25.511057216712878, 4.250128812806402, 0.05, -25.712731971922988, 4.0334951042022, 0.05, -25.90359607904889, 3.817282142518003, 0.05, -26.083669023798514, 3.6014588949925064, 0.05, -26.252968775682966, 3.385995037689014, 0.05, -26.41151183136814, 3.1708611137034803, 0.05, -26.559313263696318, 2.9560286465635324, 0.05, -26.696386776058812, 2.7414702472498775, 0.05, -26.822744759536224, 2.527159669548234, 0.05, -26.938398352315964, 2.313071855594818, 0.05, -27.04335749955833, 2.099182944847333, 0.05, -27.137631012452264, 1.8854702578787268, 0.05, -27.221226625609393, 1.6719122631425798, 0.05, -27.294151051363325, 1.4584885150786389, 0.05, -27.356410030198987, 1.245179576713245, 0.05, -27.408091522790446, 1.0336298518291935, 0.05, -27.44981510199143, 0.8344715840196462, 0.05, -27.48264868009791, 0.6566715621295844, 0.05, -27.50765921694437, 0.5002107369291455, 0.05, -27.52591294463297, 0.36507455377202985, 0.05, -27.53847555809115, 0.2512522691636158, 0.05, -27.546412372948083, 0.15873629713868398, 0.05, -27.550788454218306, 0.08752162540445171, 0.05, -27.552668717463973, 0.037605264913344066, 0.05, -27.553118002458252, 0.00898569988558091, 0.05, -27.553118002458252, 0.0, 0.05, +124 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0028493706468430188, 0.04611784771946907, 0.48757434569372926, 0.05 +0.008037577836269037, 0.10376414378852038, 1.1529259213810261, 0.05 +0.01726088378516051, 0.1844661189778294, 1.6140395037861806, 0.05 +0.03167185279941795, 0.28821938028514876, 2.075065226146387, 0.05 +0.05242268676320885, 0.4150166792758181, 2.5359459798133863, 0.05 +0.08066504040467459, 0.5648470728293149, 2.996607871069936, 0.05 +0.11754979141016536, 0.7376950201098151, 3.4569589456100047, 0.05 +0.16422675670519582, 0.933539305900609, 3.9168857158158765, 0.05 +0.22184434819753246, 1.1523518298467328, 4.3762504789224765, 0.05 +0.29097313766192046, 1.3825757892877595, 4.604479188820534, 0.05 +0.3716060364847306, 1.6126579764562035, 4.6016437433688795, 0.05 +0.4637344739925855, 1.842568750157098, 4.59821547401789, 0.05 +0.567348266924623, 2.0722758586407504, 4.594142169673048, 0.05 +0.6824354746868561, 2.301744155244661, 4.589365932078211, 0.05 +0.8089822456649084, 2.530935419561046, 4.5838252863276985, 0.05 +0.9469726554218749, 2.759808195139329, 4.577455511565667, 0.05 +1.0963885415118302, 2.9883177217991035, 4.570190533195486, 0.05 +1.2572093385823653, 3.216415941410703, 4.561964392231994, 0.05 +1.4294119187129724, 3.4440516026121406, 4.552713224028748, 0.05 +1.6129704408006373, 3.6711704417532984, 4.5423767828231565, 0.05 +1.8078562149561013, 3.897715483109277, 4.530900827119568, 0.05 +2.0140375872188447, 4.123627445254871, 4.518239242911886, 0.05 +2.230907902565874, 4.337406306940584, 4.275577233714252, 0.05 +2.457288306751917, 4.527608083720862, 3.8040355356055677, 0.05 +2.692001962408193, 4.694273113125521, 3.3333005880931843, 0.05 +2.9338748601587747, 4.837457955011633, 2.863696837722234, 0.05 +3.1817366102555393, 4.957235001935287, 2.3955409384730864, 0.05 +3.4344211892515, 5.053691579919218, 1.9291315596786163, 0.05 +3.690767618023382, 5.126928575437632, 1.46473991036828, 0.05 +3.949620550876374, 5.177058657059842, 1.0026016324441933, 0.05 +4.209830758875731, 5.204204159987147, 0.5429100585461022, 0.05 +4.470255496482681, 5.208494752138988, 0.08581184303682932, 0.05 +4.730323717255528, 5.201364415456947, -0.14260673364082876, 0.05 +4.990032286206045, 5.194171379010333, -0.14386072893227464, 0.05 +5.249378650537058, 5.186927286620256, -0.144881847801539, 0.05 +5.5083607921462505, 5.17964283218385, -0.14568908872812258, 0.05 +5.766977180029176, 5.1723277576585165, -0.14630149050667285, 0.05 +6.0252267230909915, 5.164990861236302, -0.1467379284442849, 0.05 +6.283108723772294, 5.157640013626046, -0.1470169522051279, 0.05 +6.540622832950623, 5.150282183566573, -0.14715660118945095, 0.05 +6.797769006248701, 5.142923465961549, -0.14717435210048535, 0.05 +7.0545474621881, 5.13556911878797, -0.14708694347158158, 0.05 +7.310958642219394, 5.1282236006259, -0.14691036324139262, 0.05 +7.567003172893255, 5.1208906134772025, -0.1466597429739558, 0.05 +7.822681830226438, 5.113573146663659, -0.14634933627087676, 0.05 +8.077995506220201, 5.106273519875273, -0.1459925357677072, 0.05 +8.332945177820804, 5.098993432012069, -0.14560175726408886, 0.05 +8.587531878021187, 5.091734004007643, -0.14518856008852055, 0.05 +8.841756669348431, 5.084495826544891, -0.14476354925504253, 0.05 +9.095620619550738, 5.077279004046146, -0.1443364499748867, 0.05 +9.349124779448276, 5.070083197950761, -0.14391612190770786, 0.05 +9.602270163028715, 5.062907671608766, -0.14351052683990062, 0.05 +9.855057729539675, 5.055751330219218, -0.1431268277909581, 0.05 +10.10748836764843, 5.048612762175094, -0.142771360882481, 0.05 +10.359562881575018, 5.041490278531751, -0.14244967286686006, 0.05 +10.611281979117477, 5.034381950849191, -0.14216655365119735, 0.05 +10.862646261549308, 5.027285648636638, -0.14192604425106836, 0.05 +11.11365621529755, 5.020199074964836, -0.14173147343603532, 0.05 +11.36431220541472, 5.013119802343409, -0.14158545242853648, 0.05 +11.614614470744426, 5.006045306594122, -0.14148991498574404, 0.05 +11.864563120810006, 4.998973001311609, -0.14144610565026028, 0.05 +12.114158134378458, 4.991900271369041, -0.1414545988513538, 0.05 +12.363399359700152, 4.984824506433882, -0.14151529870318313, 0.05 +12.612286516424195, 4.977743134480872, -0.14162743906020125, 0.05 +12.860819199205157, 4.970653655619246, -0.14178957723251173, 0.05 +13.108996883013052, 4.963553676157913, -0.14199958922667122, 0.05 +13.356818930176278, 4.956440943264528, -0.14225465786768865, 0.05 +13.604284599210233, 4.949313380679099, -0.14255125170858918, 0.05 +13.851393055455544, 4.942169124906211, -0.1428851154577515, 0.05 +14.098143383601975, 4.935006562928639, -0.14325123955144292, 0.05 +14.34453460209919, 4.927824369944291, -0.14364385968695714, 0.05 +14.59056567960882, 4.9206215501926165, -0.14405639503349832, 0.05 +14.836235553472966, 4.913397477282911, -0.1444814581941145, 0.05 +15.081543150276792, 4.906151936076519, -0.1449108241278374, 0.05 +15.326487408614131, 4.89888516674677, -0.1453353865949758, 0.05 +15.571067304054294, 4.891597908803269, -0.14574515887002093, 0.05 +15.815281876350902, 4.884291445932158, -0.1461292574222206, 0.05 +16.05913025892891, 4.876967651560193, -0.1464758874393013, 0.05 +16.302611710736183, 4.8696290361454535, -0.14677230829478916, 0.05 +16.545725650266633, 4.862278790608983, -0.14700491072941801, 0.05 +16.78847169194298, 4.854920833526926, -0.14715914164113997, 0.05 +17.030849684542257, 4.847559851985509, -0.147219630828328, 0.05 +17.272859751783898, 4.840201344832798, -0.14717014305421827, 0.05 +17.51450233475133, 4.832851659348634, -0.14699370968328296, 0.05 +17.75577823603801, 4.825518025733638, -0.1466726722999212, 0.05 +17.996688665306472, 4.818208585369219, -0.1461888072883788, 0.05 +18.237235285961855, 4.810932413107669, -0.14552344523099947, 0.05 +18.477420262549376, 4.803699531750428, -0.14465762714483077, 0.05 +18.71724630841778, 4.7965209173680785, -0.1435722876469825, 0.05 +18.9565651656544, 4.786377144732395, -0.20287545271367335, 0.05 +19.194710661159903, 4.762909910110074, -0.4693446924464162, 0.05 +19.430653564427708, 4.718858065356121, -0.8810368950790526, 0.05 +19.663371035276985, 4.654349416985543, -1.2901729674115714, 0.05 +19.891846221580007, 4.569503726060415, -1.6969138185025479, 0.05 +20.11506774244814, 4.464430417362685, -2.101466173954609, 0.05 +20.33202907015459, 4.339226554129018, -2.5040772646733345, 0.05 +20.541727828396578, 4.193975164839733, -2.9050277857857054, 0.05 +20.7431650284857, 4.028744001782411, -3.3046232611464355, 0.05 +20.935344268215665, 3.8435847945993573, -3.703184143661078, 0.05 +21.117420635445555, 3.641527344597785, -4.041149000031448, 0.05 +21.289063101409933, 3.432849319287599, -4.173560506203717, 0.05 +21.4503024391353, 3.2247867545073485, -4.161251295605011, 0.05 +21.60116648682368, 3.01728095376761, -4.150116014794767, 0.05 +21.7416802702936, 2.810275669398384, -4.140105687384521, 0.05 +21.871866144012273, 2.6037174743734486, -4.131163900498711, 0.05 +21.991743944734086, 2.3975560144362578, -4.123229198743816, 0.05 +22.101331153941658, 2.1917441841514056, -4.116236605697043, 0.05 +22.20064306347531, 1.9862381906730944, -4.110119869566224, 0.05 +22.289692940355064, 1.780997537595066, -4.104813061560568, 0.05 +22.368492186657697, 1.575984926052685, -4.100252230847619, 0.05 +22.43705049168686, 1.371166100583249, -4.096376509388722, 0.05 +22.495375972290663, 1.166509612076043, -4.093129770144119, 0.05 +22.543624103164117, 0.9649626174690856, -4.030939892139147, 0.05 +22.5824595914292, 0.7767097653016639, -3.7650570433484343, 0.05 +22.61290749786116, 0.6089581286392204, -3.3550327332488705, 0.05 +22.635991585737152, 0.4616817575198848, -2.945527422386712, 0.05 +22.65273464603491, 0.3348612059552092, -2.5364110312935115, 0.05 +22.664158764001243, 0.2284823593266118, -2.1275769325719476, 0.05 +22.67128553526082, 0.14253542519154502, -1.7189386827013353, 0.05 +22.675136237216417, 0.07701403911192585, -1.3104277215923834, 0.05 +22.676731960959806, 0.031914474867778625, -0.9019912848829444, 0.05 +22.67709370674013, 0.007234915606483806, -0.49359118522589635, 0.05 +22.67709370674013, 0.0, -0.1446983121296761, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueMidProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueMidProfile.csv index 232fe0bf..21a0f714 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueMidProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueMidProfile.csv @@ -1,75 +1,63 @@ -74 -3.6515143980233797E-4, 0.014606057592093519, 0.05, -0.0018257571990116896, 0.02921211518418703, 0.05, -0.005112120157232723, 0.06572725916442065, 0.05, -0.010954543194070115, 0.11684846073674782, 0.05, -0.02008332918912855, 0.18257571990116866, 0.05, -0.03322878102201292, 0.2629090366576873, 0.05, -0.05112120157232821, 0.3578484110063058, 0.05, -0.07449089371967879, 0.46739384294701175, 0.05, -0.10406816034366939, 0.591545332479812, 0.05, -0.14058330432390467, 0.7303028796047056, 0.05, -0.184401477100187, 0.8763634555256467, 0.05, -0.23552267867251228, 1.0224240314465054, 0.05, -0.29394690904086845, 1.1684846073671233, 0.05, -0.35967416820526915, 1.314545183288014, 0.05, -0.4327044561657144, 1.460605759208905, 0.05, -0.51303777292225, 1.6066663351307098, 0.05, -0.6006741184748451, 1.7527269110519028, 0.05, -0.6956134928234896, 1.8987874869728905, 0.05, -0.7978558959681841, 2.044848062893889, 0.05, -0.9074013279089099, 2.190908638814517, 0.05, -1.0242497886455415, 2.3369692147326293, 0.05, -1.1484012781782122, 2.483029790653415, 0.05, -1.2798557965069222, 2.6290903665741983, 0.05, -1.418613343631672, 2.775150942494995, 0.05, -1.5646739195524613, 2.921211518415787, 0.05, -1.7180375242692896, 3.067272094336566, 0.05, -1.8787041577821577, 3.213332670257363, 0.05, -2.046308668651263, 3.3520902173821066, 0.05, -2.2201207539970023, 3.4762417069147844, 0.05, -2.3994101109397707, 3.5857871388553697, 0.05, -2.5834464365999654, 3.6807265132038935, 0.05, -2.771499428097981, 3.7610598299603115, 0.05, -2.962838782554215, 3.826787089124677, 0.05, -3.156734197089062, 3.8779082906969453, 0.05, -3.3524553688229197, 3.9144234346771523, 0.05, -3.549271994876183, 3.936332521065262, 0.05, -3.74619484482278, 3.9384569989319473, 0.05, -3.9422346882349224, 3.920796868242844, 0.05, -4.136661222232846, 3.888530679958464, 0.05, -4.328744143936937, 3.841658434081836, 0.05, -4.517753150467593, 3.780180130613111, 0.05, -4.702957938945205, 3.704095769552236, 0.05, -4.883628206490163, 3.613405350899157, 0.05, -5.059033650222861, 3.5081088746539635, 0.05, -5.228443967263689, 3.3882063408165664, 0.05, -5.39112885473304, 3.253697749387019, 0.05, -5.546616937298711, 3.1097616513134163, 0.05, -5.694801991068302, 2.9637010753918247, 0.05, -5.835684016041815, 2.817640499470251, 0.05, -5.969263012219246, 2.6715799235486237, 0.05, -6.095538979600597, 2.525519347627032, 0.05, -6.214511918185869, 2.3794587717054227, 0.05, -6.326181827975059, 2.2333981957838134, 0.05, -6.43054870896817, 2.0873376198622218, 0.05, -6.527612561165201, 1.9412770439406124, 0.05, -6.617373384566151, 1.795216468019003, 0.05, -6.699831179171023, 1.649155892097447, 0.05, -6.774985944979814, 1.5030953161758198, 0.05, -6.842837681992526, 1.3570347402542282, 0.05, -6.903386390209157, 1.2109741643326188, 0.05, -6.956632069629708, 1.0649135884110272, 0.05, -7.002574720254179, 0.9188530124894179, 0.05, -7.04121434208257, 0.7727924365678263, 0.05, -7.072809862662285, 0.6319104115942942, 0.05, -7.097985360980534, 0.5035099663649767, 0.05, -7.117471139916924, 0.3897155787278095, 0.05, -7.131997502351062, 0.29052724868275703, 0.05, -7.142294751162557, 0.2059449762298904, 0.05, -7.149093189231017, 0.13596876136920955, 0.05, -7.15312311943605, 0.08059860410066122, 0.05, -7.155114844657263, 0.03983450442426317, 0.05, -7.155798667774268, 0.01367646234008646, 0.05, -7.155904891666667, 0.0021244778479889703, 0.05, -7.155904891666667, 0.0, 0.05, +62 +5.518719377827497E-4, 0.022074877511309987, 0.44149755022619974, 0.05 +0.0027593596889137462, 0.044149755022619926, 0.44149755022619874, 0.05 +0.007726207128958482, 0.09933694880089469, 1.1037438755654954, 0.05 +0.016556158133482456, 0.17659902009047948, 1.5452414257916958, 0.05 +0.030352956578051277, 0.2759359688913764, 1.9867389760179381, 0.05 +0.050220346338231074, 0.3973477952035959, 2.4282365262443903, 0.05 +0.07726207128958693, 0.5408344990271169, 2.869734076470419, 0.05 +0.11258187530768432, 0.7063960803619479, 3.31123162669662, 0.05 +0.15728350226808885, 0.8940325392080908, 3.7527291769228577, 0.05 +0.2124706960463661, 1.1037438755655449, 4.194226727149082, 0.05 +0.278695328580279, 1.3244926506782577, 4.414975502254257, 0.05 +0.3559573998698403, 1.5452414257912261, 4.414975502259368, 0.05 +0.4442569099150539, 1.7659902009042716, 4.414975502260909, 0.05 +0.5435938587159874, 1.9867389760186693, 4.414975502287954, 0.05 +0.6539682462725801, 2.2074877511318536, 4.414975502263685, 0.05 +0.7753800725848322, 2.4282365262450423, 4.414975502263774, 0.05 +0.9078293376527141, 2.648985301357638, 4.414975502251917, 0.05 +1.0513160414760856, 2.8697340764674273, 4.414975502195784, 0.05 +1.205840184055101, 3.0904828515803073, 4.414975502257601, 0.05 +1.3714017653897603, 3.3112316266931874, 4.414975502257601, 0.05 +1.5480007854800637, 3.5319804018060674, 4.414975502257601, 0.05 +1.735085372388229, 3.741691738163304, 4.194226727144734, 0.05 +1.931551782238691, 3.929328197009241, 3.7527291769187343, 0.05 +2.136296271155887, 4.094889778343913, 3.311231626693445, 0.05 +2.348215095264251, 4.238376482167281, 2.8697340764673562, 0.05 +2.566204510688219, 4.3597883084793665, 2.4282365262417116, 0.05 +2.789160773552227, 4.4591252572801565, 1.9867389760158005, 0.05 +3.01598013998071, 4.53638732856966, 1.545241425790067, 0.05 +3.2455588660981047, 4.591574522347894, 1.103743875564689, 0.05 +3.4767932080288455, 4.624686838614815, 0.6622463253384225, 0.05 +3.708360449604746, 4.631344831518014, 0.13315985806396924, 0.05 +3.938937874656209, 4.6115485010292545, -0.3959266097751879, 0.05 +4.167421739307274, 4.569677293021295, -0.8374241601591947, 0.05 +4.39270829968237, 4.505731207501924, -1.278921710387415, 0.05 +4.613693811905928, 4.419710244471151, -1.7204192606154578, 0.05 +4.829274532102377, 4.311614403928985, -2.161916810843323, 0.05 +5.038346716396147, 4.18144368587539, -2.6034143610718985, 0.05 +5.239806620911666, 4.029198090310384, -3.044911911300119, 0.05 +5.432550501773365, 3.854877617233985, -3.486409461527984, 0.05 +5.615474615105673, 3.658482266646157, -3.9279070117565595, 0.05 +5.787694189326541, 3.444391484417366, -4.281815644575815, 0.05 +5.948876324791702, 3.2236427093032205, -4.414975502282914, 0.05 +6.099021021501159, 3.002893934189128, -4.414975502281848, 0.05 +6.238128279454911, 2.7821451590750534, -4.414975502281493, 0.05 +6.366198098652958, 2.5613963839609255, -4.414975502282559, 0.05 +6.4832304790952975, 2.3406476088467976, -4.414975502282559, 0.05 +6.5892254207819345, 2.1198988337327407, -4.414975502281138, 0.05 +6.684182923712864, 1.899150058618595, -4.414975502282914, 0.05 +6.768102987888089, 1.6784012835045026, -4.414975502281848, 0.05 +6.84098561330761, 1.4576525083904102, -4.414975502281848, 0.05 +6.902830799971425, 1.2369037332763, -4.4149755022822035, 0.05 +6.953857520173056, 1.0205344040326203, -4.327386584873594, 0.05 +6.9948366181438075, 0.8195819594150322, -4.019048892351762, 0.05 +7.026871837759252, 0.6407043923088906, -3.577551342122831, 0.05 +7.05106692289496, 0.4839017027141601, -3.1360537918946108, 0.05 +7.068525617426501, 0.3491738906308228, -2.6945562416667457, 0.05 +7.080351665229444, 0.23652095605886103, -2.253058691439236, 0.05 +7.087648810179363, 0.1459428989983813, -1.8115611412095944, 0.05 +7.091520796151826, 0.07743971944925931, -1.37006359098244, 0.05 +7.093071367022404, 0.031011417411548337, -0.9285660407542196, 0.05 +7.093404266666668, 0.006657992885283903, -0.48706849052528867, 0.05 +7.093404266666668, 0.0, -0.13315985770567806, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueRightProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueRightProfile.csv index 70e35a8b..202f8f28 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueRightProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueRightProfile.csv @@ -1,87 +1,78 @@ -86 -3.7017853445287896E-4, 0.014807141378115157, 0.05, -0.0016921394570048205, 0.02643921845103883, 0.05, -0.004666426190032321, 0.05948573466055001, 0.05, -0.009953618981807112, 0.1057438558354958, 0.05, -0.0182137606750263, 0.1652028338643838, 0.05, -0.030106014149610654, 0.23784506949168704, 0.05, -0.04628823398289823, 0.3236443966657515, 0.05, -0.06741645227655294, 0.42256436587309404, 0.05, -0.09414427978206732, 0.5345565501102876, 0.05, -0.12712222210621618, 0.6595588464829771, 0.05, -0.1666675017387818, 0.7909055926513128, 0.05, -0.2127647350426466, 0.9219446660772956, 0.05, -0.26539601571541094, 1.0526256134552872, 0.05, -0.3245409546486245, 1.1828987786642704, 0.05, -0.3901767432139689, 1.3127157713068887, 0.05, -0.4622782458765161, 1.4420300532509447, 0.05, -0.5408181329996137, 1.5707977424619504, 0.05, -0.6257670641911204, 1.698978623830133, 0.05, -0.7170939354755962, 1.8265374256895157, 0.05, -0.8147662058105416, 1.9534454066989075, 0.05, -0.9187503203130215, 2.079682290049598, 0.05, -1.0290122485390232, 2.2052385645200334, 0.05, -1.1455181582653982, 2.3301181945274987, 0.05, -1.2682352454451007, 2.4543417435940516, 0.05, -1.3971327388959172, 2.5779498690163294, 0.05, -1.532183096471051, 2.7010071515026755, 0.05, -1.6733634011287704, 2.823606093154388, 0.05, -1.8206569574010205, 2.9458711254450036, 0.05, -1.9740550734259867, 3.067962320499326, 0.05, -2.1335589941572337, 3.1900784146249404, 0.05, -2.2991819283735935, 3.312458684327194, 0.05, -2.470951083145825, 3.4353830954446223, 0.05, -2.64890959083827, 3.5591701538489033, 0.05, -2.832800649350584, 3.6778211702462853, 0.05, -3.0220685881811944, 3.7853587766122048, 0.05, -3.2161746083743026, 3.882120403862164, 0.05, -3.4145930211379087, 3.9683682552721193, 0.05, -3.6168064333176795, 4.044268243595412, 0.05, -3.822300189052243, 4.109875114691273, 0.05, -4.030556471156197, 4.1651256420790945, 0.05, -4.241048510084791, 4.209840778571855, 0.05, -4.453235331434484, 4.243736426993869, 0.05, -4.666419996762849, 4.263693306567294, 0.05, -4.879881461975177, 4.269229304246576, 0.05, -5.093010941632829, 4.262589593153028, 0.05, -5.305175013472596, 4.243281436795333, 0.05, -5.515716171214607, 4.210823154840226, 0.05, -5.723954258685282, 4.164761749413495, 0.05, -5.929188548489517, 4.104685796084701, 0.05, -6.130700232001076, 4.030233670231179, 0.05, -6.327755112708295, 3.9410976141443714, 0.05, -6.519606334546638, 3.837024436766867, 0.05, -6.705640401073302, 3.7206813305332957, 0.05, -6.885577391496246, 3.5987398084588667, 0.05, -7.059334121440281, 3.4751345988807008, 0.05, -7.226831644101072, 3.349950453215831, 0.05, -7.387995576936922, 3.223278656717004, 0.05, -7.542756247374249, 3.095213408746523, 0.05, -7.691048706315533, 2.9658491788256813, 0.05, -7.8328126486942296, 2.835278847573941, 0.05, -7.9679922709614175, 2.7035924453437574, 0.05, -8.096536088381209, 2.5708763483958106, 0.05, -8.218396729338517, 2.4372128191461697, 0.05, -8.333530718963072, 2.3026797924911104, 0.05, -8.441898261282086, 2.1673508463802658, 0.05, -8.543463026334766, 2.0312953010536114, 0.05, -8.638191946208725, 1.8945783974791823, 0.05, -8.726055023294826, 1.757261541722045, 0.05, -8.80702515209755, 1.6194025760544901, 0.05, -8.881077955863415, 1.4810560753173019, 0.05, -8.948191638005172, 1.3422736428351407, 0.05, -9.00834684859866, 1.2031042118697524, 0.05, -9.061526565769109, 1.0635943434089905, 0.05, -9.107715991054025, 0.9237885056983494, 0.05, -9.146902458825611, 0.7837293554317276, 0.05, -9.179224552895427, 0.6464418813963082, 0.05, -9.205174784437139, 0.5190046308342339, 0.05, -9.22545056283123, 0.4055155678818394, 0.05, -9.24075136604892, 0.30601606435379985, 0.05, -9.251778247487715, 0.22053762877590605, 0.05, -9.259233416714075, 0.1491033845271714, 0.05, -9.26381988946414, 0.09172945500130648, 0.05, -9.26624120377774, 0.04842628627202022, 0.05, -9.267201199586989, 0.019199916184981482, 0.05, -9.267403860820044, 0.004053224661124549, 0.05, -9.267403860820044, 0.0, 0.05, +77 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002547922338573533, 0.04008888155407936, 0.366995022385935, 0.05 +0.007057750126825648, 0.09019655576504229, 1.0021534842192585, 0.05 +0.015074634755412781, 0.16033769257174263, 1.4028227361340067, 0.05 +0.02759951191324668, 0.250497543156678, 1.8031970116987073, 0.05 +0.045632106247810486, 0.3606518866912761, 2.2030868706919624, 0.05 +0.07017033579254328, 0.4907645908946558, 2.602254084067593, 0.05 +0.10220959018186551, 0.6407850877864446, 3.000409937835776, 0.05 +0.14274187669920899, 0.8106457303468695, 3.3972128512084976, 0.05 +0.19275482839742641, 1.0002590339643485, 3.7922660723495794, 0.05 +0.2527309468282781, 1.1995223686170342, 3.985266693053715, 0.05 +0.3226484478963113, 1.398350021360664, 3.976553054872598, 0.05 +0.4024817005466407, 1.5966650530065873, 3.9663006329184647, 0.05 +0.4922011468105695, 1.7943889252785756, 3.9544774454397658, 0.05 +0.5917732280809598, 1.991441625407806, 3.9410540025846075, 0.05 +0.7011603254155562, 2.187741946691928, 3.926006425682438, 0.05 +0.8203207268880163, 2.383208029449202, 3.9093216551454812, 0.05 +0.949208636825964, 2.5777581987589557, 3.8910033861950755, 0.05 +1.0877742466501221, 2.771312196483163, 3.8710799544841468, 0.05 +1.2359638920671863, 2.963792908341281, 3.84961423716236, 0.05 +1.3937203271800964, 3.155128702258203, 3.8267158783384403, 0.05 +1.5609831527126452, 3.3452565106509766, 3.802556167855471, 0.05 +1.7376894431877534, 3.5341258095021644, 3.777385977023755, 0.05 +1.9232855267844553, 3.7119216719340375, 3.5559172486374635, 0.05 +2.1167342542962513, 3.868974550235916, 3.1410575660375706, 0.05 +2.317009657382493, 4.00550806172483, 2.730670229778287, 0.05 +2.5230989770541816, 4.121786393433771, 2.325566634178813, 0.05 +2.7340044184447576, 4.218108827811515, 1.9264486875548847, 0.05 +2.9487445000579706, 4.29480163226426, 1.533856089054897, 0.05 +3.166354859065542, 4.352207180151429, 1.1481109577433735, 0.05 +3.3858883852105803, 4.39067052290077, 0.7692668549868209, 0.05 +3.6064145828935934, 4.410523953660261, 0.3970686151898306, 0.05 +3.8270181098526592, 4.412070539181317, 0.030931710421118197, 0.05 +4.047274962316693, 4.405137049280669, -0.13866979801296253, 0.05 +4.267246740094348, 4.399435555553101, -0.11402987455136682, 0.05 +4.486999049585689, 4.3950461898268385, -0.08778731452524724, 0.05 +4.706600666997822, 4.392032348242658, -0.060276831683605536, 0.05 +4.926122588390229, 4.390438427848138, -0.031878407890406635, 0.05 +5.14563699818124, 4.390288195820223, -0.0030046405582950797, 0.05 +5.365216193176365, 4.391583899902489, 0.02591408164532183, 0.05 +5.584931502407609, 4.394306184624881, 0.054445694447835535, 0.05 +5.804852243168238, 4.398414815212578, 0.08217261175394341, 0.05 +6.025044751452367, 4.403850165682595, 0.10870700940033728, 0.05 +6.245198333898607, 4.403071648924784, -0.01557033515622308, 0.05 +6.4645142044679185, 4.38631741138623, -0.33508475077107747, 0.05 +6.682073725568025, 4.351190422002128, -0.702539787682035, 0.05 +6.896942619376865, 4.297377876176792, -1.0762509165067335, 0.05 +7.108169743702181, 4.22454248650632, -1.4567077934094286, 0.05 +7.314786697226674, 4.132339070489871, -1.8440683203289865, 0.05 +7.515808185804885, 4.020429771564221, -2.2381859785129876, 0.05 +7.710233035993695, 3.8884970037761937, -2.638655355760555, 0.05 +7.897045722284494, 3.7362537258159825, -3.044865559204224, 0.05 +8.075218266397918, 3.5634508822685067, -3.4560568709495154, 0.05 +8.244094143940764, 3.3775175508569246, -3.7186666282316416, 0.05 +8.403503777439798, 3.1881926699807033, -3.786497617524427, 0.05 +8.553387786400394, 2.9976801792119177, -3.8102498153757125, 0.05 +8.693689252998295, 2.8060293319580074, -3.833016945078205, 0.05 +8.824354315768986, 2.6133012554138184, -3.85456153088378, 0.05 +8.94533258016446, 2.4195652879094784, -3.8747193500867994, 0.05 +9.05657738727957, 2.224896142302183, -3.8933829121459063, 0.05 +9.158045973195842, 2.0293717183254465, -3.9104884795347328, 0.05 +9.24969954879504, 1.8330715119839447, -3.926004126830036, 0.05 +9.331503321870176, 1.6360754615027286, -3.939921009624321, 0.05 +9.403426479659453, 1.4384631557855494, -3.952246114343585, 0.05 +9.465442147068162, 1.2403133481741662, -3.9629961522276647, 0.05 +9.517527330149933, 1.04170366163543, -3.9721937307747224, 0.05 +9.560051072228802, 0.850474841577378, -3.8245764011610417, 0.05 +9.59388610464899, 0.6767006484037414, -3.4754838634727303, 0.05 +9.62002061763165, 0.522690259653181, -3.080207775011208, 0.05 +9.639446461056858, 0.3885168685041588, -2.6834678229804454, 0.05 +9.653158247802333, 0.27423573490951025, -2.2856226718929706, 0.05 +9.662152589415125, 0.1798868322558513, -1.8869780530731788, 0.05 +9.667427461601264, 0.10549744372278529, -1.4877877706613203, 0.05 +9.669981693568813, 0.051084639350972884, -1.088256087436248, 0.05 +9.670814581254183, 0.016657753707390224, -0.6885377128716532, 0.05 +9.670925619978238, 0.002220774481126446, -0.28873958452527554, 0.05 +9.670925619978238, 0.0, -0.04441548962252892, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftBlueShootProfile.csv b/RoboRIO/src/main/resources/calciferLeftBlueShootProfile.csv index 7513afbb..e56bd7af 100644 --- a/RoboRIO/src/main/resources/calciferLeftBlueShootProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftBlueShootProfile.csv @@ -1,71 +1,61 @@ -70 -3.6991337507886974E-4, 0.014796535003154788, 0.05, -0.0014795140591760817, 0.022192013681944237, 0.05, -0.003976042036736644, 0.04993055955121125, 0.05, -0.008414068209497088, 0.08876052345520888, 0.05, -0.015347882360877554, 0.1386762830276093, 0.05, -0.025331377460271986, 0.19966990198788864, 0.05, -0.038918004079956665, 0.27173253239369355, 0.05, -0.056660890583616876, 0.3548577300732042, 0.05, -0.07911327267214903, 0.449047641770643, 0.05, -0.10682942906310634, 0.5543231278191463, 0.05, -0.14008920800928348, 0.6651955789235426, 0.05, -0.17890036945725873, 0.7762232289595052, 0.05, -0.22327837139634707, 0.8875600387817665, 0.05, -0.2732493857086022, 0.9994202862451022, 0.05, -0.3288537025555004, 1.112086336937964, 0.05, -0.3901494260734083, 1.2259144703581577, 0.05, -0.45721630671173025, 1.3413376127664385, 0.05, -0.5301594897516375, 1.458863660798146, 0.05, -0.6091128962899821, 1.579068130766891, 0.05, -0.6942419033400666, 1.70258014100169, 0.05, -0.7857449725544662, 1.8300613842879911, 0.05, -0.8838539072656506, 1.9621786942236892, 0.05, -0.9888325091142163, 2.0995720369713124, 0.05, -1.1009735593452936, 2.242821004621548, 0.05, -1.2205942521464408, 2.3924138560229435, 0.05, -1.3477247318021746, 2.542609593114676, 0.05, -1.4820770580840255, 2.6870465256370184, 0.05, -1.6233254834332622, 2.824968506984734, 0.05, -1.7710964438050305, 2.955419207435364, 0.05, -1.924962149479102, 3.0773141134814317, 0.05, -2.0844378008080726, 3.189513026579414, 0.05, -2.248981945999895, 3.2908829038364464, 0.05, -2.41799917353098, 3.3803445506216936, 0.05, -2.590844208724552, 3.4569007038714448, 0.05, -2.766706236352503, 3.5172405525590165, 0.05, -2.944726151850752, 3.5603983099649805, 0.05, -3.1241244797252516, 3.58796655748999, 0.05, -3.3040875636697575, 3.5992616788901146, 0.05, -3.4837691506884525, 3.593631740373902, 0.05, -3.662290981435569, 3.5704366149423232, 0.05, -3.8387426472538233, 3.529033316365087, 0.05, -4.012181081907294, 3.4687686930694177, 0.05, -4.181630126784596, 3.388980897546048, 0.05, -4.346080635823829, 3.289010180784653, 0.05, -4.504629055592219, 3.1709683953677996, 0.05, -4.656757934559747, 3.0425775793505414, 0.05, -4.802219114341804, 2.909223595641136, 0.05, -4.9407723812065205, 2.771065337294332, 0.05, -5.072186500647655, 2.628282388822686, 0.05, -5.1962405660006254, 2.481081307059414, 0.05, -5.312725479288459, 2.3296982657566803, 0.05, -5.421445396052714, 2.1743983352850913, 0.05, -5.5222189932041905, 2.0154719430295462, 0.05, -5.614880456112683, 1.8532292581698506, 0.05, -5.699280123492753, 1.6879933476013944, 0.05, -5.775284770930306, 1.5200929487510773, 0.05, -5.842777551442414, 1.3498556102421595, 0.05, -5.901657641695071, 1.177601805053124, 0.05, -5.951839662861969, 1.0036404233379852, 0.05, -5.993403765860799, 0.8312820599765883, 0.05, -6.026890463902805, 0.6697339608401226, 0.05, -6.05315070250885, 0.5252047721209033, 0.05, -6.073049199674344, 0.397969943309886, 0.05, -6.0874610090131736, 0.28823618677659313, 0.05, -6.097268683092573, 0.19615348158799845, 0.05, -6.1033599671362815, 0.12182568087416798, 0.05, -6.106625964965956, 0.06531995659349128, 0.05, -6.107959733497484, 0.026675370630567102, 0.05, -6.108255276942708, 0.0059108689044763164, 0.05, -6.108255276942708, 0.0, 0.05, +60 +5.424561587941971E-4, 0.02169824635176788, 0.43396492703535755, 0.05 +0.0021888850948781425, 0.03292857872167891, 0.22460664739822062, 0.05 +0.005893299137387343, 0.07408828085018401, 0.823194042570102, 0.05 +0.012478767918867418, 0.1317093756296015, 1.1524218955883496, 0.05 +0.022768244494680095, 0.20578953151625354, 1.4816031177330407, 0.05 +0.03758467961571249, 0.2963287024206478, 1.810783418087885, 0.05 +0.057751453472872236, 0.4033354771431949, 2.140135494450942, 0.05 +0.08409340983123376, 0.5268391271672305, 2.470073000480711, 0.05 +0.11743890839102192, 0.6669099711957632, 2.801416880570655, 0.05 +0.15862346518099904, 0.8236911357995425, 3.1356232920755844, 0.05 +0.20808334168612633, 0.9891975301025459, 3.310127886060068, 0.05 +0.2658613708775095, 1.1555605838276635, 3.3272610745023523, 0.05 +0.3320257219594639, 1.3232870216390882, 3.3545287562284942, 0.05 +0.4066778839208991, 1.493043239228704, 3.395124351792318, 0.05 +0.4899610333061964, 1.665662987705946, 3.4523949695448364, 0.05 +0.582068111914318, 1.8421415721624306, 3.5295716891296935, 0.05 +0.6832487293166017, 2.0236123480456767, 3.6294155176649223, 0.05 +0.7938138704795739, 2.211302823259443, 3.7538095042753294, 0.05 +0.9141374094094133, 2.4064707785967903, 3.903359106746942, 0.05 +1.0446536770037482, 2.6103253518866962, 4.077091465798119, 0.05 +1.185406290062441, 2.815052261173852, 4.094538185743115, 0.05 +1.3360008696200454, 3.01189159115209, 3.9367865995647566, 0.05 +1.496004893421524, 3.2000804760295707, 3.7637776975496173, 0.05 +1.6649236860753076, 3.3783758530756747, 3.5659075409220797, 0.05 +1.8421826644264108, 3.545179567022064, 3.3360742789277875, 0.05 +2.0271171547755777, 3.6986898069833387, 3.0702047992254933, 0.05 +2.218969524512552, 3.8370473947394865, 2.7671517551229563, 0.05 +2.416892161800195, 3.9584527457528598, 2.428107020267465, 0.05 +2.6199542093590815, 4.0612409511777345, 2.0557641084974954, 0.05 +2.826777538068315, 4.13646657418467, 1.5045124601387094, 0.05 +3.035891843849192, 4.182286115617538, 0.916390828657363, 0.05 +3.2461271357893846, 4.204705838803848, 0.44839446372620273, 0.05 +3.4562588587062537, 4.202634458337381, -0.041427609329343085, 0.05 +3.6650101469046383, 4.175025763967689, -0.5521738873938453, 0.05 +3.871052254147473, 4.120842144856695, -1.0836723822198735, 0.05 +4.073003965914981, 4.039034235350159, -1.6361581901307254, 0.05 +4.2694310092335055, 3.9285408663704904, -2.209867379593371, 0.05 +4.45884655343119, 3.788310883953699, -2.8045996483358238, 0.05 +4.639713817839465, 3.6173452881654997, -3.4193119157639895, 0.05 +4.810880825234881, 3.4233401479083327, -3.8801028051433395, 0.05 +4.971786066582661, 3.218104826955586, -4.104706419054933, 0.05 +5.122057192020458, 3.0054225087559505, -4.253646363992711, 0.05 +5.261344621882754, 2.7857485972459233, -4.393478230200545, 0.05 +5.389324433641917, 2.5595962351832533, -4.5230472412533995, 0.05 +5.505700968445728, 2.3275306960762157, -4.641310782140753, 0.05 +5.610208829410698, 2.0901572192994067, -4.74746953553618, 0.05 +5.702614086896854, 1.8481051497231007, -4.84104139152612, 0.05 +5.782714648923811, 1.6020112405391531, -4.921878183678952, 0.05 +5.850339877713504, 1.3525045757938536, -4.99013329490599, 0.05 +5.9058074731040495, 1.1093519078109142, -4.863053359658789, 0.05 +5.950112127744982, 0.8860930928186567, -4.46517629984515, 0.05 +5.984466868506349, 0.6870948152273376, -3.979965551826381, 0.05 +6.010111391825502, 0.5128904663830581, -3.4840869768855898, 0.05 +6.028305166233803, 0.3638754881660226, -2.98029956434071, 0.05 +6.040321764089738, 0.24033195711869992, -2.4708706209464535, 0.05 +6.047444293513956, 0.14245058848435588, -1.957627372686881, 0.05 +6.050961815865454, 0.0703504470299766, -1.4420028290875855, 0.05 +6.052166662277885, 0.024096928248610403, -0.925070375627324, 0.05 +6.052352592411357, 0.0037186026694434374, -0.40756651158333934, 0.05 +6.052352592411357, 0.0, -0.07437205338886875, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedBackupProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedBackupProfile.csv index 85514559..7a60748f 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedBackupProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedBackupProfile.csv @@ -1,55 +1,49 @@ -54 -3.6998202195815923E-4, 0.014799280878326368, 0.05, -0.002039961642815852, 0.03339959241715385, 0.05, -0.005794962153935701, 0.07510001022239697, 0.05, -0.012462141029413544, 0.13334357750955686, 0.05, -0.022858188321339706, 0.2079209458385232, 0.05, -0.037782761500985376, 0.2984914635929134, 0.05, -0.05801043251177676, 0.4045534202158277, 0.05, -0.08428127613196472, 0.5254168724037591, 0.05, -0.1172902510358819, 0.6601794980783438, 0.05, -0.15767551546009065, 0.8077052884841749, 0.05, -0.2056087153419181, 0.9586639976365487, 0.05, -0.2608092204114993, 1.1040101013916241, 0.05, -0.32295418095889017, 1.2428992109478174, 0.05, -0.39167832454244633, 1.3744828716711233, 0.05, -0.4665720462774399, 1.4978744346998714, 0.05, -0.5471771210795503, 1.612101496042207, 0.05, -0.6329793042241456, 1.7160436628919067, 0.05, -0.7230544000222202, 1.801501915961492, 0.05, -0.8161083094678607, 1.8610781889128096, 0.05, -0.9108478044048208, 1.8947898987392022, 0.05, -1.005981401846215, 1.9026719488278838, 0.05, -1.1002241671062816, 1.8848553052013322, 0.05, -1.1923105664412708, 1.8417279866997838, 0.05, -1.2810203420943154, 1.7741955130608906, 0.05, -1.365222680421039, 1.6840467665344716, 0.05, -1.4439426087478764, 1.5743985665367481, 0.05, -1.5164025848926066, 1.4491995228946057, 0.05, -1.582184920723464, 1.315646716617146, 0.05, -1.6413529714920874, 1.1833610153724667, 0.05, -1.6944282905318255, 1.0615063807947647, 0.05, -1.742337075356246, 0.9581756964884075, 0.05, -1.7862589593287226, 0.8784376794495341, 0.05, -1.8274067404325165, 0.8229556220758764, 0.05, -1.8668002229282092, 0.7878696499138558, 0.05, -1.9051005845300062, 0.7660072320359376, 0.05, -1.9425411188514465, 0.748810686428807, 0.05, -1.9789849774535908, 0.7288771720428834, 0.05, -2.0141442116269666, 0.7031846834675105, 0.05, -2.047681750749109, 0.670750782442846, 0.05, -2.079186920865402, 0.6301034023258646, 0.05, -2.10823425935552, 0.5809467698023599, 0.05, -2.134419854268946, 0.523711898268523, 0.05, -2.1573816410625595, 0.45923573587227207, 0.05, -2.176856061539901, 0.38948840954683595, 0.05, -2.1928469273294287, 0.3198173157905496, 0.05, -2.2055883078942955, 0.2548276112973327, 0.05, -2.2153762666284504, 0.19575917468309573, 0.05, -2.222554113958108, 0.14355694659315155, 0.05, -2.227499835147613, 0.09891442379010444, 0.05, -2.230615675012857, 0.06231679730487111, 0.05, -2.2323197496656486, 0.03408149305583326, 0.05, -2.2330395492149613, 0.014395990986250927, 0.05, -2.2332072264911242, 0.003353545523256215, 0.05, -2.2332072264911242, 0.0, 0.05, +48 +5.227250022608844E-4, 0.020909000090435375, 0.41818000180870746, 0.05 +0.0028818435500357776, 0.047182370955497856, 0.5254674173012496, 0.05 +0.008184964339813118, 0.10606241579554682, 1.1776008968009792, 0.05 +0.01759602709640654, 0.1882212551318684, 1.6431767867264317, 0.05 +0.032258133543436436, 0.2932421289405979, 2.10041747617459, 0.05 +0.05328056113476895, 0.4204485518266502, 2.5441284577210452, 0.05 +0.08172294470399893, 0.5688476713845996, 2.9679823911589875, 0.05 +0.1185769475571522, 0.7370800570630655, 3.3646477135693176, 0.05 +0.16474574741960402, 0.9233759972490363, 3.725918803719417, 0.05 +0.22102151922874264, 1.125515436182772, 4.042788778674713, 0.05 +0.28751134838178116, 1.3297965830607705, 4.085622937559972, 0.05 +0.36366429676493633, 1.5230589676631034, 3.8652476920466583, 0.05 +0.4488432031073467, 1.7035781268482075, 3.6103831837020817, 0.05 +0.5423179747376323, 1.8694954326057123, 3.318346115150095, 0.05 +0.6427543131874438, 2.0087267689962305, 2.7846267278103642, 0.05 +0.7482751353943503, 2.1104164441381292, 2.033793502837975, 0.05 +0.8569995315771873, 2.1744879236567396, 1.2814295903722073, 0.05 +0.9670403896487758, 2.2008171614317695, 0.5265847555005987, 0.05 +1.0765058649566093, 2.189309506156668, -0.23015310550203338, 0.05 +1.1835139972391422, 2.140162645650656, -0.9829372101202338, 0.05 +1.2862328628313047, 2.0543773118432496, -1.715706676148132, 0.05 +1.3829610405771071, 1.9345635549160471, -2.3962751385440484, 0.05 +1.4722614265507679, 1.7860077194732165, -2.9711167088566137, 0.05 +1.5528784166550167, 1.6123398020849757, -3.4733583477648144, 0.05 +1.624335437853053, 1.4291404239607248, -3.6639875624850182, 0.05 +1.6872689048481855, 1.2586693399026485, -3.4094216811615263, 0.05 +1.7430512130462532, 1.1156461639613535, -2.8604635188258998, 0.05 +1.7935267525704701, 1.00951079048434, -2.1227074695402726, 0.05 +1.8405823369898338, 0.9411116883872741, -1.3679820419413158, 0.05 +1.885708990259548, 0.9025330653942857, -0.7715724598597684, 0.05 +1.9297180778979723, 0.8801817527684859, -0.44702625251599626, 0.05 +1.972677897640306, 0.8591963948466741, -0.4197071584362355, 0.05 +2.014025544506878, 0.826952937331435, -0.644869150304781, 0.05 +2.0530077181272937, 0.7796434724083129, -0.9461892984624432, 0.05 +2.0889394871871336, 0.7186353811968019, -1.2201618242302192, 0.05 +2.1211273842572815, 0.6437579414029551, -1.4975487958769373, 0.05 +2.148939148140159, 0.5562352776575521, -1.7504532749080592, 0.05 +2.1721243307138, 0.46370365147281806, -1.8506325236946808, 0.05 +2.1908569110700133, 0.37465160712426876, -1.781040886970986, 0.05 +2.2054457898840814, 0.291777576281356, -1.6574806168582557, 0.05 +2.21630205955139, 0.21712539334616485, -1.4930436587038225, 0.05 +2.223912449903052, 0.15220780703324222, -1.2983517262584525, 0.05 +2.228817076424482, 0.09809253042859939, -1.0823055320928565, 0.05 +2.231591464430492, 0.055487760120202116, -0.8520954061679454, 0.05 +2.2328325598910452, 0.02482190921106446, -0.6133170181827531, 0.05 +2.2331484395186623, 0.006317592552342437, -0.37008633317444045, 0.05 +2.233151520016541, 6.160995756805054E-5, -0.1251196518954877, 0.05 +2.233151520016541, 0.0, -0.0012321991513610108, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedBoilerToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedBoilerToLoadingProfile.csv index 25f4eecd..ba547719 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedBoilerToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedBoilerToLoadingProfile.csv @@ -1,148 +1,152 @@ -147 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002777777777777774, 0.04444444444444436, 0.05, -0.007777777777777759, 0.0999999999999997, 0.05, -0.016666666666666625, 0.1777777777777773, 0.05, -0.03055555555555596, 0.27777777777778667, 0.05, -0.05055555555555677, 0.40000000000001623, 0.05, -0.07777777777778011, 0.5444444444444668, 0.05, -0.1133333333333371, 0.7111111111111398, 0.05, -0.1583333333333382, 0.9000000000000221, 0.05, -0.21388888888887678, 1.1111111111107712, 0.05, -0.280555555555523, 1.3333333333329238, 0.05, -0.3583333333333088, 1.5555555555557166, 0.05, -0.4472222222222322, 1.7777777777784676, 0.05, -0.5472222222222709, 2.0000000000007745, 0.05, -0.6583333333333788, 2.222222222222159, 0.05, -0.780555555555479, 2.444444444442002, 0.05, -0.9138888888886788, 2.666666666663997, 0.05, -1.0583333333329787, 2.8888888888859965, 0.05, -1.2138888888883792, 3.111111111108009, 0.05, -1.380555555554879, 3.3333333333299953, 0.05, -1.558333333332479, 3.555555555551999, 0.05, -1.7472222222211788, 3.7777777777739985, 0.05, -1.947222222220979, 3.9999999999960023, 0.05, -2.1583333333318793, 4.222222222218002, 0.05, -2.380555555553879, 4.444444444439997, 0.05, -2.6138888888876117, 4.666666666674653, 0.05, -2.8583333333331686, 4.888888888911138, 0.05, -3.113333333334329, 5.100000000023206, 0.05, -3.3777777777799773, 5.288888888912968, 0.05, -3.6505555555589964, 5.45555555558038, 0.05, -3.9305555555602707, 5.600000000025487, 0.05, -4.216666666672683, 5.722222222248261, 0.05, -4.507777777785119, 5.822222222248712, 0.05, -4.802777777786462, 5.900000000026857, 0.05, -5.090773382796867, 5.759912100208103, 0.05, -5.361298023958858, 5.410492823239813, 0.05, -5.631386726356515, 5.40177404795315, 0.05, -5.900577760723904, 5.383820687347766, 0.05, -6.168926659411173, 5.366977973745374, 0.05, -6.43650421547897, 5.351551121355948, 0.05, -6.703396779926799, 5.337851288956584, 0.05, -6.969705996032306, 5.326184322110136, 0.05, -7.235547891482548, 5.316837909004842, 0.05, -7.501051292310884, 5.310068016566733, 0.05, -7.766355578640779, 5.306085726597883, 0.05, -8.031607851538146, 5.305045457947342, 0.05, -8.296959651794001, 5.30703600511711, 0.05, -8.562563411967309, 5.312075203466172, 0.05, -8.828568850132474, 5.320108763303284, 0.05, -9.095119531977245, 5.33101363689543, 0.05, -9.36234979608984, 5.3446052822519015, 0.05, -9.630382210158785, 5.360648281378931, 0.05, -9.899325662429126, 5.378869045406811, 0.05, -10.169274138533787, 5.398969522093209, 0.05, -10.440306172357527, 5.420640676474806, 0.05, -10.712484913212421, 5.4435748170978915, 0.05, -10.985858716047993, 5.4674760567114244, 0.05, -11.260462142139172, 5.492068521823585, 0.05, -11.536317252572443, 5.517102208665434, 0.05, -11.813435081871164, 5.542356585974419, 0.05, -12.091817194190472, 5.5676422463861535, 0.05, -12.371457240372628, 5.592800923643121, 0.05, -12.652342455335239, 5.617704299252228, 0.05, -12.93445505279966, 5.642251949288424, 0.05, -13.21777349019938, 5.666368747994418, 0.05, -13.502273591237039, 5.690002020753169, 0.05, -13.787929523085419, 5.713118636967592, 0.05, -14.074714631411211, 5.735702166515854, 0.05, -14.362602145052827, 5.757750272832309, 0.05, -14.651565760220814, 5.779272303359735, 0.05, -14.941580119244023, 5.80028718046418, 0.05, -15.232621198436682, 5.820821583853202, 0.05, -15.524666617185192, 5.840908374970191, 0.05, -15.817695882129746, 5.860585298891086, 0.05, -16.11169057735302, 5.879893904465485, 0.05, -16.406634510076746, 5.898878654474517, 0.05, -16.70251382118092, 5.917586222083463, 0.05, -16.999317067074816, 5.936064917877943, 0.05, -17.29703527952107, 5.95436424892507, 0.05, -17.595662006957223, 5.972534548723056, 0.05, -17.895193341932636, 5.990626699508225, 0.05, -18.195627936475486, 6.008691890856973, 0.05, -18.496967007051524, 6.026781411520745, 0.05, -18.79921432963223, 6.0449464516141, 0.05, -19.102376224203457, 6.063237891424575, 0.05, -19.406461527683792, 6.081706069606714, 0.05, -19.711481552446347, 6.100400495251089, 0.05, -20.017450027201253, 6.119369495098093, 0.05, -20.324383015394865, 6.1386597638722495, 0.05, -20.63229880579045, 6.158315807911721, 0.05, -20.94121776753049, 6.17837923480074, 0.05, -21.25116216199564, 6.198887889303052, 0.05, -21.56215589993371, 6.219874758761389, 0.05, -21.874224235124803, 6.241366703821843, 0.05, -22.187393380148652, 6.263382900476972, 0.05, -22.501690030355498, 6.285933004136926, 0.05, -22.81714078478177, 6.309015088525462, 0.05, -23.13377144629499, 6.332613230264362, 0.05, -23.45160619290441, 6.356694932188424, 0.05, -23.770666606342694, 6.381208268765652, 0.05, -24.09097055713475, 6.406079015841144, 0.05, -24.412530946450573, 6.431207786316469, 0.05, -24.73535431817873, 6.456467434563074, 0.05, -25.05943936783274, 6.481700993080232, 0.05, -25.384775389915934, 6.506720441663856, 0.05, -25.711340724482252, 6.531306691326342, 0.05, -26.03910128228383, 6.555211156031586, 0.05, -26.368009246827537, 6.578159290874092, 0.05, -26.69800206412488, 6.599856345946852, 0.05, -27.028615021973156, 6.612259156965575, 0.05, -27.35874858314983, 6.6026712235334895, 0.05, -27.68705209447869, 6.566070226577214, 0.05, -28.01215543247468, 6.502066759919837, 0.05, -28.332676350444235, 6.410418359391041, 0.05, -28.647228566198, 6.291044315075305, 0.05, -28.954429912646592, 6.144026928971887, 0.05, -29.252909853650248, 5.969598820073103, 0.05, -29.54131576842982, 5.768118295591398, 0.05, -29.818317577756343, 5.540036186530499, 0.05, -30.083000609015002, 5.293660625173181, 0.05, -30.335093445490703, 5.041856729514027, 0.05, -30.57457398662709, 4.789610822727759, 0.05, -30.801436978939684, 4.537259846251889, 0.05, -31.01569080228447, 4.285076466895752, 0.05, -31.217354453197455, 4.0332730182596785, 0.05, -31.406454835207565, 3.782007640202219, 0.05, -31.58302437997232, 3.5313908952950905, 0.05, -31.747099030456628, 3.281493009686168, 0.05, -31.89871654871807, 3.0323503652288646, 0.05, -32.0379151396684, 2.783971819006511, 0.05, -32.16473234488105, 2.536344104253083, 0.05, -32.2792041702213, 2.289436506804979, 0.05, -32.38136440946083, 2.0432047847906776, 0.05, -32.471244127160155, 1.7975943539865513, 0.05, -32.548871273737355, 1.5525429315439816, 0.05, -32.614270398095655, 1.3079824871659567, 0.05, -32.667845909778244, 1.0715102336517042, 0.05, -32.7106061541787, 0.8552048880091173, 0.05, -32.743779611905246, 0.663469154530991, 0.05, -32.76859069012283, 0.49622156435157494, 0.05, -32.78626065745737, 0.3533993466908103, 0.05, -32.79800847851207, 0.23495642109389872, 0.05, -32.805051514880816, 0.1408607273749427, 0.05, -32.80860610542716, 0.07109181092689212, 0.05, -32.80988801339626, 0.0256381593819953, 0.05, -32.810112744002865, 0.004494612132042597, 0.05, -32.810112744002865, 0.0, 0.05, +151 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002717391304347822, 0.04347826086956514, 0.4347826086956506, 0.05 +0.007608695652173897, 0.09782608695652148, 1.0869565217391268, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.029891304347826463, 0.27173913043479087, 1.956521739130609, 0.05 +0.04945652173913161, 0.391304347826103, 2.391304347826243, 0.05 +0.07608695652174138, 0.5326086956521955, 2.8260869565218494, 0.05 +0.11086956521739495, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783155, 0.8804347826087319, 3.695652173913211, 0.05 +0.20923913043477188, 1.0869565217388066, 4.130434782601495, 0.05 +0.27445652173909973, 1.304347826086557, 4.347826086955009, 0.05 +0.350543478260842, 1.5217391304348449, 4.347826086965756, 0.05 +0.4375000000000061, 1.7391304347832826, 4.3478260869687535, 0.05 +0.5353260869565658, 1.956521739131194, 4.347826086958229, 0.05 +0.6440217391304945, 2.1739130434785747, 4.347826086947615, 0.05 +0.7635869565216794, 2.3913043478236973, 4.347826086902451, 0.05 +0.8940217391302444, 2.6086956521713, 4.347826086952056, 0.05 +1.0353260869561902, 2.826086956518914, 4.347826086952278, 0.05 +1.1874999999995164, 3.0434782608665234, 4.347826086952189, 0.05 +1.350543478260223, 3.260869565214133, 4.347826086952189, 0.05 +1.5244565217383097, 3.4782608695617334, 4.347826086952011, 0.05 +1.709239130433777, 3.6956521739093473, 4.347826086952278, 0.05 +1.904891304346625, 3.9130434782569568, 4.347826086952189, 0.05 +2.1108695652159843, 4.119565217387184, 4.130434782604553, 0.05 +2.3260869565201174, 4.304347826082662, 3.695652173909547, 0.05 +2.5494565217375595, 4.467391304348842, 3.2608695653236097, 0.05 +2.779891304347304, 4.608695652194887, 2.8260869569209035, 0.05 +3.016304347826641, 4.7282608695867445, 2.391304347837142, 0.05 +3.257608695653826, 4.826086956543696, 1.9565217391390277, 0.05 +3.5027173913071152, 4.902173913065786, 1.5217391304418015, 0.05 +3.7505434782647646, 4.956521739152988, 1.0869565217440424, 0.05 +4.000000000005031, 4.989130434805329, 0.6521739130468163, 0.05 +4.2500000000061675, 5.000000000022737, 0.217391304348169, 0.05 +4.500000000007306, 5.000000000022773, 7.105427357601002E-13, 0.05 +4.750000000008443, 5.000000000022737, -7.105427357601002E-13, 0.05 +5.000000000009582, 5.000000000022773, 7.105427357601002E-13, 0.05 +5.22241254735571, 4.448250946922575, -11.034981062003961, 0.05 +5.443753129219028, 4.426811637266355, -0.42878619312439525, 0.05 +5.663725447614075, 4.399446367900928, -0.5473053873085476, 0.05 +5.882309874689655, 4.371688541511594, -0.5551565277866821, 0.05 +6.099501870787017, 4.343839921947236, -0.5569723912871538, 0.05 +6.315315334044061, 4.316269265140888, -0.551413136126957, 0.05 +6.52978597961773, 4.289412911473391, -0.5371270733499323, 0.05 +6.742974484871041, 4.263770105066225, -0.5128561281433264, 0.05 +6.954969099717575, 4.239892296930671, -0.4775561627110747, 0.05 +7.165887374072373, 4.21836548709596, -0.43053619669422005, 0.05 +7.375876637709666, 4.199785272745872, -0.37160428700175885, 0.05 +7.585112929391574, 4.184725833638156, -0.3011887821543269, 0.05 +7.793798167375192, 4.17370475967236, -0.22042147931591316, 0.05 +8.002155535096175, 4.167147354419662, -0.1311481050539598, 0.05 +8.210423261341813, 4.16535452491273, -0.035856590138649835, 0.05 +8.418847185607161, 4.1684784853069745, 0.06247920788489125, 0.05 +8.627672685458872, 4.176509997034224, 0.16063023454499614, 0.05 +8.837136633162205, 4.189278954066635, 0.25537914064821976, 0.05 +9.047460050328478, 4.206468343325463, 0.34378778517655917, 0.05 +9.258842023412754, 4.227639461685502, 0.42342236720077864, 0.05 +9.471455262436761, 4.252264780480146, 0.4925063758928694, 0.05 +9.685443467599201, 4.2797641032488105, 0.5499864553732969, 0.05 +9.900920458788285, 4.309539823781661, 0.5955144106570032, 0.05 +10.117970854678534, 4.341007917804991, 0.6293618804666146, 0.05 +10.336651981586565, 4.373622538160616, 0.6522924071124869, 0.05 +10.556996647366157, 4.40689331559186, 0.6654155486248925, 0.05 +10.779016427492675, 4.440395602530334, 0.6700457387694669, 0.05 +11.002705153882573, 4.4737745277979775, 0.6675785053528749, 0.05 +11.228042364881778, 4.506744219984101, 0.6593938437224622, 0.05 +11.45499654364968, 4.539083575358035, 0.6467871074786835, 0.05 +11.683528038295536, 4.5706298929171245, 0.6309263511817953, 0.05 +11.913591606433679, 4.601271362762828, 0.6128293969140763, 0.05 +12.145138573479587, 4.630939340918178, 0.5933595631069899, 0.05 +12.378118616845203, 4.659600867312321, 0.5732305278828598, 0.05 +12.612481207447185, 4.687251812039642, 0.5530188945464154, 0.05 +12.848176749848232, 4.713910848020942, 0.533180719626003, 0.05 +13.085157464295106, 4.73961428893747, 0.5140688183305642, 0.05 +13.323378053307867, 4.764411780255199, 0.4959498263545825, 0.05 +13.56279619451105, 4.788362824063669, 0.47902087616940037, 0.05 +13.803372892529385, 4.81153396036672, 0.4634227260610224, 0.05 +14.045072723139896, 4.833996612210224, 0.449253036870072, 0.05 +14.287863993905724, 4.855825415316557, 0.4365760621266723, 0.05 +14.531718843903205, 4.8770969999496145, 0.42543169266114234, 0.05 +14.776613298992643, 4.897889101788768, 0.4158420367830651, 0.05 +15.02252729739147, 4.918279967976513, 0.40781732375490876, 0.05 +15.269444696026413, 4.938347972698884, 0.4013600944474227, 0.05 +15.517353265919398, 4.958171397859699, 0.396468503216294, 0.05 +15.766244683638487, 4.977828354381755, 0.3931391304411136, 0.05 +16.016114522760976, 4.99739678244975, 0.39136856135989717, 0.05 +16.266962248289513, 5.016954510570769, 0.39115456242038604, 0.05 +16.518791215781498, 5.036579349839717, 0.3924967853789596, 0.05 +16.771608675148144, 5.056349187332916, 0.39539674986398765, 0.05 +17.02542577807913, 5.076342058619709, 0.39985742573586336, 0.05 +17.280257586564314, 5.096636169703728, 0.4058822216803648, 0.05 +17.53612307833448, 5.117309835403299, 0.41347331399142817, 0.05 +17.79304514339749, 5.138441301260178, 0.42262931713757723, 0.05 +18.051050564343644, 5.160108418923109, 0.4333423532586167, 0.05 +18.31016996933644, 5.1823880998559035, 0.4455936186558951, 0.05 +18.57043774483601, 5.205355509991417, 0.4593482027102702, 0.05 +18.83189189291808, 5.229082961641375, 0.4745490329991675, 0.05 +19.094573810840547, 5.253638358449361, 0.49110793615971815, 0.05 +19.35852796982766, 5.2790831797422015, 0.5088964258568041, 0.05 +19.6238014626555, 5.305469856556824, 0.5277335362924518, 0.05 +19.890443387221403, 5.332838491318039, 0.5473726952243041, 0.05 +20.158504024942225, 5.361212754416443, 0.567485261968077, 0.05 +20.42803377454513, 5.390594992058144, 0.5876447528340201, 0.05 +20.699081795796157, 5.420960425020534, 0.6073086592478028, 0.05 +20.971694320710103, 5.452250498278919, 0.6258014651676902, 0.05 +21.245912600366825, 5.484365593134447, 0.6423018971105598, 0.05 +21.521770465979483, 5.51715731225312, 0.6558343823734702, 0.05 +21.79929150887404, 5.550420857891194, 0.665270912761482, 0.05 +22.078485925953267, 5.583888341584486, 0.6693496738658311, 0.05 +22.35934711765034, 5.61722383394151, 0.6667098471404742, 0.05 +22.641848197201803, 5.6500215910292155, 0.6559551417541165, 0.05 +22.92593863181582, 5.681808692280385, 0.6357420250233936, 0.05 +23.211541307692073, 5.7120535175250335, 0.6048965048929666, 0.05 +23.498550363159403, 5.740181109346614, 0.5625518364316129, 0.05 +23.786830153936226, 5.765595815536485, 0.5082941237974126, 0.05 +24.076215687731256, 5.787710675900639, 0.44229720728308664, 0.05 +24.366514774768383, 5.805981740742547, 0.36542129683816427, 0.05 +24.657511988446444, 5.819944273561249, 0.27925065637402824, 0.05 +24.94850838116481, 5.8199278543673065, -3.283838788448179E-4, 0.05 +25.238159767697198, 5.793027730647766, -0.5380024743908152, 0.05 +25.524955914374626, 5.7359229335485935, -1.1420959419834453, 0.05 +25.807405772947067, 5.648997171448816, -1.7385152419955574, 0.05 +26.084052834478186, 5.532941230622348, -2.321118816529353, 0.05 +26.353486489667166, 5.388673103779627, -2.8853625368544122, 0.05 +26.61434863254228, 5.217242857502306, -3.4286049255464235, 0.05 +26.865335540055245, 5.019738150259246, -3.9500941448612004, 0.05 +27.105195660248643, 4.797202403867982, -4.450714927825281, 0.05 +27.33272432053182, 4.5505732056635395, -4.9325839640888525, 0.05 +27.547212262440077, 4.289758838165154, -5.216287349967708, 0.05 +27.748593579090972, 4.027626333017925, -5.242650102944584, 0.05 +27.93697545258282, 3.7676374698370085, -5.199777263618328, 0.05 +28.11246743530202, 3.5098396543839216, -5.155956309061738, 0.05 +28.275177531297164, 3.2542019199028998, -5.112754689620438, 0.05 +28.425209421930628, 3.0006378126692956, -5.071282144672082, 0.05 +28.56266059497569, 2.7490234609012036, -5.03228703536184, 0.05 +28.687621152660924, 2.4992111537046755, -4.996246143930563, 0.05 +28.80017311091686, 2.2510391651187147, -4.963439771719216, 0.05 +28.9003900645688, 2.004339073038801, -4.934001841598272, 0.05 +28.988337086483295, 1.758940438289869, -4.907972694978642, 0.05 +29.064070777391283, 1.5146738181597952, -4.885332402601477, 0.05 +29.127639419401362, 1.2713728402015874, -4.866019559164156, 0.05 +29.179526291601064, 1.0377374439940599, -4.67270792415055, 0.05 +29.22080794361706, 0.8256330403199577, -4.242088073482044, 0.05 +29.252711059644145, 0.6380623205416919, -3.7514143955653156, 0.05 +29.2764546590091, 0.47487198729912405, -3.2638066648513564, 0.05 +29.293251983234583, 0.33594648450962666, -2.7785100557899476, 0.05 +29.30431209951612, 0.22120232563073958, -2.2948831775777414, 0.05 +29.31084122506183, 0.1305825109141231, -1.8123962943323295, 0.05 +29.31404378607191, 0.06405122020161136, -1.3306258142502347, 0.05 +29.315123223710188, 0.02158875276553844, -0.8492493487214583, 0.05 +29.31528255261117, 0.003186578019631716, -0.3680434949181345, 0.05 +29.31528255261117, 0.0, -0.06373156039263432, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedLeftProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedLeftProfile.csv index db79a6da..fe5c5db2 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedLeftProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedLeftProfile.csv @@ -1,87 +1,80 @@ -86 -3.745838238938134E-4, 0.014983352955752536, 0.05, -0.002026026010285909, 0.033028843727841914, 0.05, -0.0057418868463854945, 0.07431721672199171, 0.05, -0.01234825850277969, 0.1321274331278839, 0.05, -0.022671731349035065, 0.20646945692510746, 0.05, -0.03753971131391269, 0.2973595992975525, 0.05, -0.0577808170878847, 0.4048221154794402, 0.05, -0.08422535649507676, 0.5288907881438413, 0.05, -0.11770588221284199, 0.6696105143553046, 0.05, -0.15905782506760716, 0.8270388570953031, 0.05, -0.20870634680661268, 0.9929704347801103, 0.05, -0.26666571559684044, 1.159187375804555, 0.05, -0.33295254635948024, 1.3257366152527963, 0.05, -0.4075857691891848, 1.4926644565940916, 0.05, -0.49058657849340603, 1.6600161860844247, 0.05, -0.5819783570856877, 1.827835571845633, 0.05, -0.681786567925006, 1.9961642167863671, 0.05, -0.7900386036505348, 2.1650407145105754, 0.05, -0.9067635823476821, 2.3344995739429453, 0.05, -1.0319920784330887, 2.5045699217081308, 0.05, -1.165755772810949, 2.675273887557208, 0.05, -1.3080870061759262, 2.8466246672995412, 0.05, -1.4590182198484876, 3.018624273451225, 0.05, -1.618581264347274, 3.191260889975728, 0.05, -1.78680656004002, 3.364505913854922, 0.05, -1.9637220929091463, 3.5383106573825285, 0.05, -2.149352236618735, 3.712602874191773, 0.05, -2.343716394485472, 3.8872831573347377, 0.05, -2.5468274689539, 4.062221489368566, 0.05, -2.7586901793152157, 4.2372542072263135, 0.05, -2.9792992658844315, 4.4121817313843135, 0.05, -3.2086376431927706, 4.5867675461667785, 0.05, -3.4466745872563975, 4.760738881272536, 0.05, -3.6929386766124903, 4.925281787121853, 0.05, -3.9465160461278677, 5.071547390307544, 0.05, -4.206476625440832, 5.1992115862592865, 0.05, -4.471876997207213, 5.30800743532761, 0.05, -4.741764231305401, 5.39774468196377, 0.05, -5.015180480319792, 5.468324980287808, 0.05, -5.291168031941634, 5.519751032436841, 0.05, -5.568774457773407, 5.552128516635457, 0.05, -5.847057487158281, 5.565660587697481, 0.05, -6.125073864308246, 5.560327542999299, 0.05, -6.4018983222215535, 5.5364891582661455, 0.05, -6.676641299527843, 5.494859546125779, 0.05, -6.948434743173253, 5.43586887290821, 0.05, -7.216432372024463, 5.359952577024197, 0.05, -7.479809048269394, 5.267533524898623, 0.05, -7.737759432213579, 5.159007678883697, 0.05, -7.98949611465632, 5.034733648854817, 0.05, -8.234247417052098, 4.895026047915536, 0.05, -8.471255026348182, 4.740152185921696, 0.05, -8.699786544811957, 4.5706303692754915, 0.05, -8.91952496957988, 4.394768495358456, 0.05, -9.130546380232794, 4.220428213058267, 0.05, -9.332923777793027, 4.047547951204663, 0.05, -9.526726586973467, 3.8760561836087786, 0.05, -9.712020356639195, 3.7058753933145607, 0.05, -9.888866611772915, 3.536925102674381, 0.05, -10.05732281656929, 3.3691240959275035, 0.05, -10.217442418730636, 3.2023920432269173, 0.05, -10.36927494955956, 3.036650616578478, 0.05, -10.51286616129528, 2.8718242347143756, 0.05, -10.64825818733139, 2.707840520722189, 0.05, -10.775489714383456, 2.544630541041306, 0.05, -10.894596158864227, 2.3821288896154225, 0.05, -11.00560984129348, 2.2202736485850774, 0.05, -11.108560155271661, 2.059006279563609, 0.05, -11.203473727667957, 1.8982714479259313, 0.05, -11.290374568360798, 1.738016813856816, 0.05, -11.369284208908375, 1.5781928109515577, 0.05, -11.440221828377389, 1.4187523893802838, 0.05, -11.503204367422619, 1.2596507809045836, 0.05, -11.558246629535574, 1.100845242259114, 0.05, -11.605361370105538, 0.9422948113992796, 0.05, -11.644573832472947, 0.7842492473481897, 0.05, -11.676302019051723, 0.6345637315755213, 0.05, -11.70134185572429, 0.5007967334513538, 0.05, -11.720487113112535, 0.382905147764898, 0.05, -11.73452990154346, 0.2808557686185271, 0.05, -11.74426109434773, 0.1946238560853767, 0.05, -11.750470683678524, 0.1241917866158666, 0.05, -11.75394807317064, 0.06954778984234665, 0.05, -11.755482309342781, 0.030684723442800727, 0.05, -11.755862254028914, 0.0075988937226450295, 0.05, -11.755862254028914, 0.0, 0.05, +79 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.00291596288285762, 0.0474496924397611, 0.5142112400995698, 0.05 +0.00825425010866553, 0.10676574451615817, 1.1863210415279413, 0.05 +0.017745211917152334, 0.1898192361697361, 1.6610698330715583, 0.05 +0.03257656533484402, 0.29662706835383373, 2.136156643681953, 0.05 +0.05393741165350835, 0.4272169263732865, 2.6117971603890555, 0.05 +0.08301891154149342, 0.5816299977597014, 3.088261427728297, 0.05 +0.12101509511586694, 0.7599236714874704, 3.565873474555381, 0.05 +0.1691238080600815, 0.9621742588842913, 4.045011747936417, 0.05 +0.22854779177836093, 1.1884796743655885, 4.526108309625944, 0.05 +0.299901078594333, 1.4270657363194417, 4.7717212390770625, 0.05 +0.38320793121868235, 1.6661370524869863, 4.7814263233508925, 0.05 +0.47849660076434997, 1.9057733909133527, 4.792726768527329, 0.05 +0.5857992505749184, 2.1460529962113695, 4.805592105960335, 0.05 +0.7051518301014943, 2.3870515905315157, 4.819971886402925, 0.05 +0.836593878865853, 2.628840975287175, 4.835787695113183, 0.05 +0.9801682369932929, 2.871487162548799, 4.8529237452324825, 0.05 +1.1359206348070403, 3.1150479562749487, 4.871215874522994, 0.05 +1.3038991270635854, 3.359569845130902, 4.89043777711907, 0.05 +1.484153334314015, 3.6050841450085924, 4.910285997553805, 0.05 +1.6767334484602374, 3.851602282924449, 4.930362758317131, 0.05 +1.8816889572762387, 4.099110176320028, 4.950157867911589, 0.05 +2.09906704333622, 4.347561721199629, 4.969030897592006, 0.05 +2.3283052845462575, 4.584764824200742, 4.744062060022269, 0.05 +2.5682243298999037, 4.79838090707292, 4.272321657443552, 0.05 +2.8176281669534387, 4.988076741070698, 3.793916679955558, 0.05 +3.0753027108279056, 5.153490877489338, 3.3082827283728022, 0.05 +3.3400151780551695, 5.2942493445452765, 2.815169341118775, 0.05 +3.6105143973756313, 5.4099843864092385, 2.31470083727924, 0.05 +3.885532157753496, 5.500355207557293, 1.80741642296109, 0.05 +4.163785614393372, 5.565069132797512, 1.2942785048043781, 0.05 +4.443980676793223, 5.603901247997032, 0.7766423039904069, 0.05 +4.724816198360218, 5.616710431339893, 0.25618366685721483, 0.05 +5.00559893358301, 5.615654704455838, -0.02111453768110394, 0.05 +5.286246550119672, 5.612952330733243, -0.05404747445188818, 0.05 +5.566678656094347, 5.608642119493505, -0.0862042247947592, 0.05 +5.84681806189792, 5.602788116071465, -0.11708006844081353, 0.05 +6.126591915009786, 5.5954770622373005, -0.1462210766832861, 0.05 +6.405932668457178, 5.586815068947844, -0.17323986578912098, 0.05 +6.684778855057613, 5.576923732008698, -0.1978267387829291, 0.05 +6.9630756524676825, 5.565935948201393, -0.21975567614610725, 0.05 +7.240775236455232, 5.55399167975098, -0.23888536900825486, 0.05 +7.517836930918899, 5.541233889273356, -0.25515580955246975, 0.05 +7.794227172843426, 5.527804838490532, -0.2685810156564905, 0.05 +8.069919315858593, 5.513842860303349, -0.27923956374365844, 0.05 +8.34430566211701, 5.487726925168351, -0.5223187026999554, 0.05 +8.61619558765286, 5.437798510716994, -0.9985682890271441, 0.05 +8.884407556175628, 5.364239370455353, -1.471182805232818, 0.05 +9.147777589061988, 5.267400657727223, -1.9367742545625966, 0.05 +9.405157886491736, 5.1476059485949595, -2.395894182645275, 0.05 +9.655415099931112, 5.005144268787531, -2.8492335961485615, 0.05 +9.897428385593935, 4.840265713256458, -3.297571110621469, 0.05 +10.130087350480578, 4.653179297732865, -3.7417283104718635, 0.05 +10.352289981595124, 4.444052622290918, -4.182533508838944, 0.05 +10.562940621802328, 4.213012804144083, -4.620796362936694, 0.05 +10.761521918325272, 3.971625930458872, -4.8277374737042145, 0.05 +10.948097163580906, 3.7315049051126925, -4.802420506923593, 0.05 +11.122732895324031, 3.4927146348625153, -4.775805405003544, 0.05 +11.285489911925492, 3.2551403320292303, -4.751486056665701, 0.05 +11.43642348014069, 3.018671364303949, -4.729379354505623, 0.05 +11.575583579368272, 2.7832019845516607, -4.709387595045769, 0.05 +11.703015161513653, 2.548631642907623, -4.691406832880753, 0.05 +11.818758412852894, 2.314865026784839, -4.675332322455681, 0.05 +11.922849008778519, 2.081811918512486, -4.661062165447056, 0.05 +12.015318353079357, 1.8493868860167446, -4.648500649914831, 0.05 +12.096193799097728, 1.617508920367416, -4.637559312986572, 0.05 +12.165498848421812, 1.3861009864816833, -4.628158677714653, 0.05 +12.223253325849692, 1.1550895485575865, -4.620228758481937, 0.05 +12.27003995293007, 0.9357325416075638, -4.387140139000453, 0.05 +12.307012639622451, 0.7394537338476299, -3.925576155198678, 0.05 +12.335330311489729, 0.5663534373455534, -3.4620059300415296, 0.05 +12.356148841547148, 0.4163706011483716, -2.9996567239436365, 0.05 +12.370621829530792, 0.28945975967289544, -2.538216829509523, 0.05 +12.37990125449414, 0.18558849926694038, -2.0774252081191014, 0.05 +12.38513801038801, 0.10473511787739999, -1.6170676277908076, 0.05 +12.387482329381566, 0.04688637987112253, -1.1569747601255491, 0.05 +12.38808409790887, 0.012035370546083533, -0.6970201865007799, 0.05 +12.388093066790098, 1.7937762458166762E-4, -0.2371198584300373, 0.05 +12.388093066790098, 0.0, -0.0035875524916333524, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedLoadingToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedLoadingToLoadingProfile.csv index 11358564..ee893167 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedLoadingToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedLoadingToLoadingProfile.csv @@ -1,130 +1,125 @@ -129 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.0026851747138675816, 0.04259238316624052, 0.05, -0.007476855641324603, 0.09583361854914042, 0.05, -0.01599552892919767, 0.17037346575746132, 0.05, -0.02930628808757451, 0.2662151831675368, 0.05, -0.04847449459951719, 0.3833641302388536, 0.05, -0.07456591127366433, 0.5218283334829427, 0.05, -0.10864686466962895, 0.6816190679192925, 0.05, -0.15178444113518838, 0.8627515293111885, 0.05, -0.20504671679913974, 1.065245513279027, 0.05, -0.2689702915836587, 1.2784714956903787, 0.05, -0.3435601208764837, 1.4917965858564992, 0.05, -0.4288220928494919, 1.7052394394601638, 0.05, -0.5247630750663452, 1.9188196443370658, 0.05, -0.6313909654440127, 2.13255780755335, 0.05, -0.7487147472474908, 2.3464756360695596, 0.05, -0.87674454676219, 2.560595990293986, 0.05, -1.0154916925732058, 2.7749429162203154, 0.05, -1.1649687755350622, 2.989541659237128, 0.05, -1.3251897077330759, 3.2044186439602744, 0.05, -1.4961697796557618, 3.4196014384537197, 0.05, -1.6779257134438945, 3.6351186757626555, 0.05, -1.8704757115647346, 3.8509999624167994, 0.05, -2.073839498606074, 4.06727574082679, 0.05, -2.288038355796498, 4.28397714380847, 0.05, -2.5130951460678705, 4.501135805427454, 0.05, -2.74903432905303, 4.718783659703191, 0.05, -2.995345136422939, 4.926216147398175, 0.05, -3.2509793915170153, 5.11268510188152, 0.05, -3.514886702697122, 5.2781462236021355, 0.05, -3.7860140140768985, 5.422546227595529, 0.05, -4.063305189150795, 5.545823501477933, 0.05, -4.345700635821864, 5.64790893342139, 0.05, -4.632136980593041, 5.7287268954235175, 0.05, -4.921546797632536, 5.788196340789907, 0.05, -5.212858396918181, 5.826231985712897, 0.05, -5.504995673913552, 5.84274553990741, 0.05, -5.797419811194931, 5.848482745627597, 0.05, -6.090131913098494, 5.854242038071262, 0.05, -6.383132829367054, 5.86001832537119, 0.05, -6.676423179282017, 5.865806998299258, 0.05, -6.970003375200745, 5.871603918374581, 0.05, -7.263873645445374, 5.877405404892578, 0.05, -7.558034056336524, 5.883208217823008, 0.05, -7.852484533378792, 5.889009540845369, 0.05, -8.14722488149655, 5.89480696235517, 0.05, -8.442254804232057, 5.900598454710145, 0.05, -8.737573921945163, 5.906382354262109, 0.05, -9.03318178894024, 5.912157339901539, 0.05, -9.329077909465108, 5.917922410497341, 0.05, -9.625261752733966, 5.92367686537715, 0.05, -9.921732766744634, 5.929420280213367, 0.05, -10.21849039110816, 5.935152487270516, 0.05, -10.515534068788602, 5.940873553608844, 0.05, -10.812863256793273, 5.946583760093419, 0.05, -11.11047743584548, 5.952283581044158, 0.05, -11.40837611904565, 5.957973664003413, 0.05, -11.706558859554391, 5.963654810174832, 0.05, -12.005025257301561, 5.9693279549434095, 0.05, -12.303774964751895, 5.974994149006682, 0.05, -12.602807691734162, 5.980654539645341, 0.05, -12.902123209366977, 5.986310352656281, 0.05, -13.201721353077119, 5.991962874202859, 0.05, -13.50160202472869, 5.997613433031446, 0.05, -13.801765193869757, 6.003263382821345, 0.05, -14.102210898101324, 6.008914084631334, 0.05, -14.402939242569493, 6.014566889363393, 0.05, -14.703950398579176, 6.020223120193646, 0.05, -15.005244601322833, 6.025884054873122, 0.05, -15.306822146717838, 6.0315509079001055, 0.05, -15.608683387344422, 6.037224812531699, 0.05, -15.910828727473413, 6.042906802579819, 0.05, -16.213258617133302, 6.048597793197757, 0.05, -16.515973545267393, 6.054298562681832, 0.05, -16.81897403189672, 6.060009732586542, 0.05, -17.122260619306928, 6.065731748204206, 0.05, -17.425833862204172, 6.071464857944854, 0.05, -17.729694316887713, 6.077209093670809, 0.05, -18.033842529318687, 6.082964248619449, 0.05, -18.338279022155856, 6.088729856743398, 0.05, -18.64300428074405, 6.094505171763937, 0.05, -18.948018737964095, 6.1002891444008265, 0.05, -19.253322758045112, 6.106080401620347, 0.05, -19.558916619304476, 6.111877225187266, 0.05, -19.864800495754352, 6.117677528997551, 0.05, -20.170974437794136, 6.123478840795671, 0.05, -20.4774383518117, 6.129278280351262, 0.05, -20.78419197888475, 6.135072541460995, 0.05, -21.09123487261578, 6.140857874620618, 0.05, -21.398566376156374, 6.146630070811888, 0.05, -21.70618559858762, 6.152384448624906, 0.05, -22.01400233119454, 6.156334652138372, 0.05, -22.32135477071553, 6.147048790419809, 0.05, -22.627096122509904, 6.114827035887494, 0.05, -22.930075201424945, 6.059581578300818, 0.05, -23.229136591253603, 5.981227796573176, 0.05, -23.52312086533785, 5.879685481684984, 0.05, -23.81086486537881, 5.7548800008191945, 0.05, -24.091202034397433, 5.606743380372432, 0.05, -24.36296279743873, 5.435215260825936, 0.05, -24.624974982351393, 5.2402436982532485, 0.05, -24.876154061192274, 5.023581576817602, 0.05, -25.115989550084656, 4.7967097778476475, 0.05, -25.344457236581015, 4.569353729927185, 0.05, -25.56153450169778, 4.341545302335266, 0.05, -25.76720030335422, 4.113316033128804, 0.05, -25.961435149990994, 3.8846969327354883, 0.05, -26.1442210651241, 3.6557183026621245, 0.05, -26.31554154467443, 3.4264095910066206, 0.05, -26.47538150754086, 3.196799257328572, 0.05, -26.623727242052805, 2.966914690238931, 0.05, -26.76056634850118, 2.73678212896748, 0.05, -26.885887680144815, 2.5064266328727283, 0.05, -26.999681283520463, 2.2758720675129687, 0.05, -27.101938339331625, 2.045141116223207, 0.05, -27.192651105431665, 1.8142553220007698, 0.05, -27.27181286256167, 1.5832351426001128, 0.05, -27.33941786397862, 1.3521000283390057, 0.05, -27.395551609490262, 1.1226749102328453, 0.05, -27.44087909815408, 0.906549773276375, 0.05, -27.4765546360837, 0.7135107585924306, 0.05, -27.503733483496468, 0.5435769482553262, 0.05, -27.5235716288282, 0.3967629066346157, 0.05, -27.537225598828478, 0.2730794000055542, 0.05, -27.545852299721208, 0.17253401785456812, 0.05, -27.55060888832414, 0.09513177205863277, 0.05, -27.55265267149888, 0.04087566349480605, 0.05, -27.5531410317309, 0.009767204640353718, 0.05, -27.5531410317309, 0.0, 0.05, +124 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0025854119335149465, 0.04083867345290763, 0.38199086036250035, 0.05 +0.007179813347359452, 0.0918880282768901, 1.0209870964796495, 0.05 +0.015347811675516694, 0.16335996656314483, 1.4294387657250944, 0.05 +0.028110754995930565, 0.2552588664082774, 1.837977996902651, 0.05 +0.046490353840977064, 0.36759197690092993, 2.2466622098530507, 0.05 +0.07150886476798897, 0.5003702185402381, 2.6555648327861636, 0.05 +0.10418932038878234, 0.6536091124158674, 3.0647778775125856, 0.05 +0.14555581121985223, 0.8273298166213974, 3.4744140841105997, 0.05 +0.1966338307295617, 1.0215603901941894, 3.884611471455841, 0.05 +0.2579397529882633, 1.226118445174033, 4.091161099596872, 0.05 +0.3294806555745737, 1.430818051726207, 4.09399213104348, 0.05 +0.41126509623558866, 1.6356888132202991, 4.097415229881842, 0.05 +0.5033032446275962, 1.840762967840151, 4.101483092397036, 0.05 +0.6056070258964534, 2.046075625377145, 4.106253150739878, 0.05 +0.7181902758353826, 2.2516649987785833, 4.111787468028769, 0.05 +0.8410689025186091, 2.4575725336645298, 4.11815069771893, 0.05 +0.974261051868657, 2.663842987000956, 4.125409066728523, 0.05 +1.1177872727934455, 2.8705244184957692, 4.133628629896267, 0.05 +1.271670677856719, 3.07766810126547, 4.142873655394013, 0.05 +1.4359370937656248, 3.285328318178114, 4.1532043382528805, 0.05 +1.610615197425694, 3.49356207320138, 4.16467510046532, 0.05 +1.7957366325723652, 3.702428702933423, 4.177332594640859, 0.05 +1.9908211034895862, 3.9016894183444184, 3.985214308219911, 0.05 +2.194873577223827, 4.081049474684815, 3.587201126807935, 0.05 +2.4068970104945158, 4.2404686654137755, 3.1883838145792076, 0.05 +2.625891536778161, 4.379890525672905, 2.7884372051825856, 0.05 +2.8508536728215144, 4.499242720867072, 2.3870439038833524, 0.05 +3.0807755699548864, 4.598437942667445, 1.9839044360074531, 0.05 +3.314644334035373, 4.677375281609731, 1.5787467788457121, 0.05 +3.551441434949181, 4.735942018276164, 1.1713347333286706, 0.05 +3.7901422216008442, 4.774015733033264, 0.7614742951419906, 0.05 +4.029715554408041, 4.791466656143938, 0.3490184622134862, 0.05 +4.269645533788407, 4.798599587607317, 0.14265862926757578, 0.05 +4.509935291292673, 4.805795150085321, 0.14391124956008028, 0.05 +4.750587375968236, 4.813041693511264, 0.1449308685188555, 0.05 +4.991603801901597, 4.820328518667221, 0.14573650311914932, 0.05 +5.232986095854485, 4.8276458790577506, 0.14634720781058874, 0.05 +5.474735344496594, 4.834984972842182, 0.1467818756886352, 0.05 +5.716852240774151, 4.842337925551144, 0.1470590541792305, 0.05 +5.959337129135625, 4.849697767229477, 0.14719683356666735, 0.05 +6.202190049148683, 4.857058400261148, 0.14721266063341787, 0.05 +6.445410777445142, 4.864414565929178, 0.14712331336060203, 0.05 +6.688998867652001, 4.871761804137171, 0.14694476415986202, 0.05 +6.932953688280094, 4.879096412561862, 0.14669216849380717, 0.05 +7.177274458426441, 4.886415402926946, 0.1463798073016953, 0.05 +7.421960281125061, 4.893716453972406, 0.14602102090918834, 0.05 +7.667010174559921, 4.900997868697183, 0.14562829449554116, 0.05 +7.912423100840634, 4.908258525614267, 0.1452131383416777, 0.05 +8.158197992604462, 4.915497835276548, 0.14478619324561848, 0.05 +8.404333777328343, 4.922715694477614, 0.1443571840213309, 0.05 +8.650829399402578, 4.929912441484713, 0.14393494014196762, 0.05 +8.897683840148979, 4.9370888149279875, 0.1435274688654964, 0.05 +9.144896135658277, 4.944245910185956, 0.14314190515937852, 0.05 +9.392465392634909, 4.951385139532642, 0.1427845869337041, 0.05 +9.640390802278555, 4.958508192872918, 0.14246106680552373, 0.05 +9.88867165223924, 4.965616999213733, 0.14217612681630243, 0.05 +10.137307336735388, 4.972713689922952, 0.14193381418438733, 0.05 +10.386297364842692, 4.979800562146073, 0.14173744446241088, 0.05 +10.635641367051939, 4.9868800441849475, 0.14158964077749303, 0.05 +10.885339100066307, 4.993954660287369, 0.14149232204843543, 0.05 +11.135390449920079, 5.0010269970754315, 0.1414467357612459, 0.05 +11.385795433406392, 5.008099669726264, 0.14145345301665557, 0.05 +11.63655419783077, 5.015175288487589, 0.14151237522648685, 0.05 +11.887667019087447, 5.022256425133508, 0.14162273291837835, 0.05 +12.139134298052507, 5.029345579301202, 0.14178308335388579, 0.05 +12.390956555265285, 5.036445144255573, 0.14199129908742947, 0.05 +12.64313442386942, 5.043557372082664, 0.14224455654181511, 0.05 +12.895668640791834, 5.050684338448288, 0.14253932731246977, 0.05 +13.1485600360937, 5.057827906037332, 0.1428713517808866, 0.05 +13.401809520467497, 5.064989687475912, 0.14323562877160967, 0.05 +13.655418070767508, 5.072171006000239, 0.14362637048654037, 0.05 +13.909386713611193, 5.079372856873681, 0.14403701746882547, 0.05 +14.163716506902047, 5.0865958658170785, 0.1444601788679556, 0.05 +14.418408519230777, 5.093840246574619, 0.14488761515080384, 0.05 +14.673463807151276, 5.101105758409969, 0.14531023670700804, 0.05 +14.928883390226524, 5.108391661504983, 0.14571806190028624, 0.05 +15.184668223803028, 5.115696671530081, 0.14610020050195516, 0.05 +15.440819169495413, 5.123018913847687, 0.14644484635212507, 0.05 +15.697336963452843, 5.130355879148594, 0.14673930601812657, 0.05 +15.954222182231625, 5.137704375575645, 0.14696992854101865, 0.05 +16.211475206555146, 5.145060486470401, 0.1471222178951237, 0.05 +16.46909618277868, 5.152419524470699, 0.1471807600059627, 0.05 +16.72708498241623, 5.159775992750936, 0.14712936560474787, 0.05 +16.985441159703406, 5.167123545743542, 0.14695105985211399, 0.05 +17.244163907505676, 5.174454956045379, 0.1466282060367341, 0.05 +17.503252011780507, 5.181762085496591, 0.14614258902424737, 0.05 +17.762703804940127, 5.1890358631923705, 0.1454755539155883, 0.05 +18.022517118496634, 5.196266271130111, 0.14460815875480648, 0.05 +18.28268923543892, 5.203442338845694, 0.14352135431165536, 0.05 +18.543051714423086, 5.2072495796833, 0.07614481675211948, 0.05 +18.80286708774597, 5.196307466457677, -0.21884226451245326, 0.05 +19.060990702354978, 5.162472292180205, -0.6767034855494458, 0.05 +19.316271519667527, 5.105616346250972, -1.1371189185846475, 0.05 +19.56755251688817, 5.025619944412896, -1.599928036761522, 0.05 +19.81367120214763, 4.922373705189226, -2.064924784473412, 0.05 +20.05346023088707, 4.795780574788721, -2.531862608010087, 0.05 +20.28574810573366, 4.645757496931797, -3.0004615571384896, 0.05 +20.509359938172135, 4.472236648769485, -3.4704169632462367, 0.05 +20.723118248029223, 4.275166197141793, -3.9414090325538353, 0.05 +20.926010753963112, 4.057850118677807, -4.346321569279716, 0.05 +21.117598228832478, 3.8317494973873356, -4.522012425809434, 0.05 +21.297849888440567, 3.605033192161813, -4.5343261045104555, 0.05 +21.46673788128731, 3.3777598569349303, -4.545466704537651, 0.05 +21.624237166622155, 3.1499857066968744, -4.555483004761118, 0.05 +21.7703253744084, 2.921764155724909, -4.564431019439308, 0.05 +21.90498265137853, 2.6931455394025807, -4.572372326446565, 0.05 +22.02819149952206, 2.464176962870631, -4.579371530638996, 0.05 +22.13993661073317, 2.234902224222215, -4.585494772968319, 0.05 +22.240204702358994, 2.0053618325165017, -4.5908078341142655, 0.05 +22.328984357292867, 1.7755930986774537, -4.595374676780959, 0.05 +22.406265872798834, 1.545630310119356, -4.599255771161954, 0.05 +22.472041119676415, 1.3155049375516363, -4.602507451354394, 0.05 +22.526471311697666, 1.0886038404250196, -4.538021942532335, 0.05 +22.57029538852542, 0.8764815365550438, -4.242446077399515, 0.05 +22.60466219510887, 0.6873361316690135, -3.7829080977206053, 0.05 +22.630721876886902, 0.521193635560638, -3.32284992216751, 0.05 +22.649625553213593, 0.37807352653383347, -2.862402180536091, 0.05 +22.662525050402614, 0.2579899437804288, -2.401671655068094, 0.05 +22.670572685501746, 0.160952701982661, -1.9407448359553552, 0.05 +22.67492109384697, 0.08696816690443929, -1.4796907015644345, 0.05 +22.676723096938474, 0.036040061830107675, -1.0185621014866322, 0.05 +22.67713160813054, 0.00817022384131122, -0.5573967597759291, 0.05 +22.67713160813054, 0.0, -0.1634044768262244, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedMidProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedMidProfile.csv index 922a0b99..947268d2 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedMidProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedMidProfile.csv @@ -1,75 +1,63 @@ -74 -3.657674863723679E-4, 0.014630699454894716, 0.05, -0.001828837431861839, 0.029261398909789422, 0.05, -0.005120744809213143, 0.06583814754702606, 0.05, -0.010973024591171015, 0.11704559563915744, 0.05, -0.020117211750480188, 0.18288374318618345, 0.05, -0.03328484125988563, 0.2633525901881088, 0.05, -0.051207448092132395, 0.3584521366449353, 0.05, -0.0746165672199649, 0.4681823825566501, 0.05, -0.10424373361612793, 0.5925433279232606, 0.05, -0.14082048225336619, 0.7315349727447651, 0.05, -0.18471258061805215, 0.8778419672937193, 0.05, -0.23592002871018172, 1.0241489618425914, 0.05, -0.29444282652974263, 1.1704559563912187, 0.05, -0.36028097407674875, 1.3167629509401224, 0.05, -0.43343447135119995, 1.463069945489024, 0.05, -0.5139033183531415, 1.6093769400388314, 0.05, -0.6016875150825439, 1.7556839345880482, 0.05, -0.6967870615393964, 1.9019909291370496, 0.05, -0.7992019577236992, 2.0482979236860555, 0.05, -0.9089322036354358, 2.1946049182347327, 0.05, -1.0259777992744765, 2.340911912780812, 0.05, -1.1503387446409574, 2.487218907329618, 0.05, -1.282015039734878, 2.6335259018784107, 0.05, -1.4210066845562388, 2.7798328964272168, 0.05, -1.5673136791050397, 2.9261398909760183, 0.05, -1.7209360233812807, 3.07244688552482, 0.05, -1.8818737173849616, 3.218753880073617, 0.05, -2.0497609936297105, 3.3577455248949795, 0.05, -2.2238663171427837, 3.4821064702614635, 0.05, -2.4034581529514365, 3.5918367161730558, 0.05, -2.587804966082926, 3.6869362626297875, 0.05, -2.7761752215645066, 3.767405109631614, 0.05, -2.967837384423436, 3.833243257178589, 0.05, -3.162059919686969, 3.884450705270659, 0.05, -3.3581112923823624, 3.921027453907868, 0.05, -3.5552599675368715, 3.9429735030901814, 0.05, -3.7525312695408855, 3.94542604008028, 0.05, -3.9489505227831505, 3.928385064845301, 0.05, -4.143786192290735, 3.896713390151696, 0.05, -4.336306743090891, 3.8504110160031146, 0.05, -4.525780640210868, 3.7894779423995395, 0.05, -4.7114763486779205, 3.7139141693410593, 0.05, -4.8926623335193, 3.6237196968275853, 0.05, -5.068607059762257, 3.5188945248591352, 0.05, -5.238578992434045, 3.3994386534357623, 0.05, -5.4018465965619145, 3.2653520825573956, 0.05, -5.557921477810899, 3.1214976249796855, 0.05, -5.706681009332403, 2.9751906304300846, 0.05, -5.848125191126426, 2.828883635880466, 0.05, -5.982254023192968, 2.6825766413308294, 0.05, -6.10906750553203, 2.5362696467812462, 0.05, -6.228565638143611, 2.3899626522316275, 0.05, -6.340748421027711, 2.243655657681991, 0.05, -6.4456158541843305, 2.09734866313239, 0.05, -6.543167937613471, 1.951041668582807, 0.05, -6.633404671315129, 1.8047346740331704, 0.05, -6.716326055289306, 1.658427679483534, 0.05, -6.791932089536004, 1.5121206849339508, 0.05, -6.86022277405522, 1.365813690384332, 0.05, -6.921198108846957, 1.2195066958347311, 0.05, -6.974858093911212, 1.0731997012851124, 0.05, -7.021202729247986, 0.926892706735476, 0.05, -7.06023201485728, 0.780585712185875, 0.05, -7.092189091376872, 0.6391415303918357, 0.05, -7.117682866930918, 0.5098755110809172, 0.05, -7.137444876492164, 0.3952401912249215, 0.05, -7.152206655033357, 0.2952355708238663, 0.05, -7.162699737527248, 0.20986164987782274, 0.05, -7.169655658946584, 0.13911842838671973, 0.05, -7.173805954264112, 0.08300590635055727, 0.05, -7.1758821584525805, 0.04152408376937089, 0.05, -7.176615806484739, 0.014672960643178357, 0.05, -7.176738433333331, 0.00245253697183756, 0.05, -7.176738433333331, 0.0, 0.05, +62 +5.49931793657908E-4, 0.02199727174631632, 0.4399454349263264, 0.05 +0.0027496589682895374, 0.043994543492632585, 0.43994543492632526, 0.05 +0.007699045111210697, 0.09898772285842318, 1.0998635873158118, 0.05 +0.016497953809737204, 0.1759781739705301, 1.5398090222421381, 0.05 +0.030246248651184988, 0.27496589682895567, 1.9797544571685115, 0.05 +0.05004379322287049, 0.39595089143370993, 2.419699892095085, 0.05 +0.07699045111210907, 0.5389331577847717, 2.859645327021235, 0.05 +0.11218608590621662, 0.7039126958821509, 3.299590761947584, 0.05 +0.156730561192509, 0.8908895057258472, 3.739536196873927, 0.05 +0.2117237405583021, 1.0998635873158618, 4.17948163180029, 0.05 +0.27771555579723384, 1.3198363047786348, 4.3994543492554605, 0.05 +0.3547060069093173, 1.5398090222416694, 4.399454349260692, 0.05 +0.4426950938945572, 1.7597817397047977, 4.399454349262566, 0.05 +0.5416828167530191, 1.9797544571692383, 4.399454349288812, 0.05 +0.6516691754846433, 2.1997271746324842, 4.39945434926492, 0.05 +0.7726541700894299, 2.4196998920957324, 4.399454349264964, 0.05 +0.9046378005673469, 2.639672609558339, 4.39945434925213, 0.05 +1.0476200669182596, 2.8596453270182565, 4.399454349198351, 0.05 +1.20160096914232, 3.079618044481207, 4.399454349259013, 0.05 +1.3665805072395272, 3.2995907619441445, 4.399454349258747, 0.05 +1.5425586812098822, 3.5195634794070996, 4.399454349259102, 0.05 +1.7289855592597265, 3.7285375609968874, 4.179481631795756, 0.05 +1.924761277801746, 3.9155143708403894, 3.7395361968700414, 0.05 +2.1287859732486254, 4.0804939089375925, 3.29959076194406, 0.05 +2.339959782013051, 4.223476175288514, 2.859645327018434, 0.05 +2.5571828405077075, 4.344461169893128, 2.419699892092275, 0.05 +2.77935528514528, 4.4434488927514515, 1.9797544571664716, 0.05 +3.0053772523384548, 4.520439343863494, 1.5398090222408456, 0.05 +3.2341488784999153, 4.57543252322921, 1.0998635873143314, 0.05 +3.4645703000423484, 4.608428430848663, 0.6599181523890607, 0.05 +3.6952836182124607, 4.614266363402244, 0.11675865107161343, 0.05 +3.9249309342554115, 4.592946320859017, -0.42640085086453894, 0.05 +4.152412384583538, 4.5496290065625455, -0.8663462859294313, 0.05 +4.376628105609524, 4.484314420519713, -1.306291720856656, 0.05 +4.596478233746043, 4.3970025627303855, -1.7462371557865453, 0.05 +4.81086290540578, 4.2876934331947325, -2.1861825907130594, 0.05 +5.0186822570014105, 4.156387031912612, -2.6261280256424158, 0.05 +5.218836424945615, 4.003083358884094, -3.066073460570351, 0.05 +5.410225545651072, 3.8277824141091443, -3.506018895498997, 0.05 +5.5917497555304605, 3.630484197587762, -3.9459643304276426, 0.05 +5.76256722616338, 3.416349412658395, -4.2826956985873466, 0.05 +5.922386060923093, 3.1963766951942496, -4.399454349282905, 0.05 +6.071206259809596, 2.976403977730069, -4.399454349283616, 0.05 +6.209027822822892, 2.7564312602659236, -4.399454349282905, 0.05 +6.335850749962979, 2.536458542801725, -4.399454349283971, 0.05 +6.4516750412298585, 2.3164858253375975, -4.39945434928255, 0.05 +6.55650069662353, 2.0965131078734345, -4.3994543492832605, 0.05 +6.650327716143992, 1.876540390409236, -4.399454349283971, 0.05 +6.7331560997912465, 1.6565676729450907, -4.399454349282905, 0.05 +6.804985847565294, 1.4365949554809454, -4.399454349282905, 0.05 +6.86581695946613, 1.216622238016729, -4.399454349284326, 0.05 +6.915907470660681, 1.0018102238910132, -4.296240282514319, 0.05 +6.956065348109526, 0.8031575489768983, -3.9730534982822974, 0.05 +6.987390455399983, 0.6265021458091447, -3.5331080633550727, 0.05 +7.010982656119375, 0.47184401438784107, -3.0931626284260716, 0.05 +7.0279418138550245, 0.33918315471298754, -2.6532171934970705, 0.05 +7.039367792194249, 0.22851956678449525, -2.213271758569846, 0.05 +7.046360454724372, 0.13985325060245302, -1.7733263236408447, 0.05 +7.050019665032712, 0.07318420616680754, -1.3333808887129095, 0.05 +7.051445286706593, 0.02851243347761212, -0.8934354537839084, 0.05 +7.051737183333333, 0.005837932534795698, -0.45349001885632845, 0.05 +7.051737183333333, 0.0, -0.11675865069591396, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedRightProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedRightProfile.csv index ad15e2f9..e2064808 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedRightProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedRightProfile.csv @@ -1,90 +1,79 @@ -89 -3.676470588235294E-4, 0.014705882352941176, 0.05, -0.0017097498540497296, 0.026842055904524, 0.05, -0.004729396123935256, 0.060392925397710524, 0.05, -0.01009736545163474, 0.10735938655398972, 0.05, -0.01848407260178277, 0.16773414300296058, 0.05, -0.030559334262946887, 0.24150523322328232, 0.05, -0.046992077518013355, 0.32865486510132935, 0.05, -0.06844998821859863, 0.4291582140117054, 0.05, -0.09559910034124157, 0.5429822424528588, 0.05, -0.12910332434586416, 0.6700844800924517, 0.05, -0.16928912195252843, 0.8037159521332851, 0.05, -0.21614595205312095, 0.9371366020118506, 0.05, -0.2696614987938767, 1.0703109348151147, 0.05, -0.329821671019745, 1.2032034445173667, 0.05, -0.3966106077145758, 1.3357787338966156, 0.05, -0.4700106914537919, 1.4680016747843212, 0.05, -0.5500025747289856, 1.599837665503874, 0.05, -0.6365652216117506, 1.731252937655298, 0.05, -0.7296759711099986, 1.86221498996496, 0.05, -0.8293106263924763, 1.992693105649554, 0.05, -0.9354435783896635, 2.1226590399437426, 0.05, -1.048047969922119, 2.2520878306491103, 0.05, -1.1670959109176158, 2.380958819909935, 0.05, -1.2925587523016493, 2.5092568276806704, 0.05, -1.424407431877781, 2.6369735915226333, 0.05, -1.5626129018093897, 2.764109398632172, 0.05, -1.7071466497126861, 2.8906749580659263, 0.05, -1.857981325228538, 3.016693510317039, 0.05, -2.0150914805019524, 3.142203105468287, 0.05, -2.1784544331172206, 3.2672590523053637, 0.05, -2.3480512525362336, 3.391936388380262, 0.05, -2.523867867907056, 3.516332307416449, 0.05, -2.705896283979742, 3.640568321453719, 0.05, -2.89413588279508, 3.7647919763067574, 0.05, -3.0882708977107756, 3.8827002983139063, 0.05, -3.287673567674331, 3.988053399271111, 0.05, -3.4917292919551532, 4.081114485616442, 0.05, -3.6998358667287135, 4.162131495471202, 0.05, -3.9114020813353445, 4.231324292132617, 0.05, -4.125845698382969, 4.2888723409524925, 0.05, -4.342590895163337, 4.334903935607348, 0.05, -4.561065294068034, 4.3694879780939395, 0.05, -4.780696751217819, 4.392629142995704, 0.05, -5.00091009738166, 4.404266923276818, 0.05, -5.221242152648908, 4.406641105344947, 0.05, -5.441221715382804, 4.399591254677917, 0.05, -5.6602489410533705, 4.380544513411323, 0.05, -5.877711313054277, 4.349247440018129, 0.05, -6.092982454596043, 4.305422830835302, 0.05, -6.305421560031021, 4.248782108699563, 0.05, -6.514373404208663, 4.179036883552846, 0.05, -6.719168855580936, 4.095909027445462, 0.05, -6.919125798994287, 3.9991388682670292, 0.05, -7.113550365725463, 3.888491334623522, 0.05, -7.3019498754976215, 3.767990195443172, 0.05, -7.48415828246454, 3.644168139338353, 0.05, -7.6601289633537375, 3.51941361778396, 0.05, -7.8298151938914975, 3.393724610755199, 0.05, -7.993170840617741, 3.267112934524874, 0.05, -8.150150894634509, 3.1396010803353533, 0.05, -8.300711872039823, 3.0112195481062956, 0.05, -8.444812104266544, 2.8820046445344425, 0.05, -8.582411938666827, 2.7519966880056557, 0.05, -8.713473868357752, 2.6212385938185294, 0.05, -8.837962604937278, 2.489774731590527, 0.05, -8.955845108440352, 2.357650070061463, 0.05, -9.067090584243166, 2.224909516056268, 0.05, -9.171670455816939, 2.0915974314754466, 0.05, -9.269558320647244, 1.9577572966061187, 0.05, -9.360729894142235, 1.8234314698998062, 0.05, -9.445162946891008, 1.6886610549754455, 0.05, -9.522837238121998, 1.5534858246197971, 0.05, -9.593734448235226, 1.417944202264556, 0.05, -9.657838112704043, 1.2820732893763287, 0.05, -9.715133558755369, 1.1459089210265037, 0.05, -9.765607845690829, 1.0094857387091811, 0.05, -9.809249710744979, 0.8728373010830112, 0.05, -9.846049519810622, 0.7359961813128608, 0.05, -9.876217524670762, 0.603360097202798, 0.05, -9.900309029927005, 0.4818301051248469, 0.05, -9.919006140655833, 0.37394221457656823, 0.05, -9.93299251133133, 0.2797274135099162, 0.05, -9.942952970510582, 0.19920918358503856, 0.05, -9.949573201594573, 0.13240462167983322, 0.05, -9.953539476830136, 0.07932550471124195, 0.05, -9.95553844257758, 0.03997931494889993, 0.05, -9.956256954657173, 0.014370241591824914, 0.05, -9.956381962998595, 0.0025001668284417525, 0.05, -9.956381962998595, 0.0, 0.05, +78 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002507879065196211, 0.039288016086532915, 0.35097771303500613, 0.05 +0.0069275633156599, 0.08839368500927379, 0.9821133784548175, 0.05 +0.014784036600622876, 0.1571294656992595, 1.3747156137997143, 0.05 +0.027057870634535727, 0.24547668067825698, 1.7669442995799494, 0.05 +0.04472810924914524, 0.35340477229219025, 2.1585618322786653, 0.05 +0.06877152268837053, 0.4808682687845058, 2.5492699298463104, 0.05 +0.10016171507013927, 0.6278038476353746, 2.9387115770173753, 0.05 +0.13986808301558157, 0.7941273589088458, 3.3264702254694245, 0.05 +0.1888546303890839, 0.9797309474700463, 3.7120717712240103, 0.05 +0.24758941546309102, 1.1746957014801422, 3.899295080201919, 0.05 +0.3160457440330161, 1.3691265713985012, 3.88861739836718, 0.05 +0.3941925905500562, 1.5629369303408014, 3.876207178846003, 0.05 +0.4819947185358387, 1.7560425597156504, 3.8621125874969797, 0.05 +0.5794128707632953, 1.9483630445491318, 3.846409696669628, 0.05 +0.6864040523611583, 2.1398236319572606, 3.8292117481625754, 0.05 +0.8029219398678854, 2.330357750134542, 3.8106823635456255, 0.05 +0.9289174504853913, 2.5199102123501174, 3.7910492443115107, 0.05 +1.064339515870335, 2.7084413076988745, 3.7706219069751423, 0.05 +1.2091361065938702, 2.8959318144707025, 3.74981013543656, 0.05 +1.3632555609938495, 3.0823890879995868, 3.729145470577686, 0.05 +1.5266482698138109, 3.2678541763992266, 3.7093017679927964, 0.05 +1.699268765526361, 3.4524099142510045, 3.6911147570355585, 0.05 +1.8806003404203586, 3.6266314978799543, 3.484431672578996, 0.05 +2.0696630117245403, 3.7812534260836332, 3.0924385640735785, 0.05 +2.265496754561558, 3.916674856740351, 2.708428613134357, 0.05 +2.467162809049132, 4.033321089751491, 2.3329246602227904, 0.05 +2.6737439222665613, 4.1316222643485805, 1.9660234919417974, 0.05 +2.8843433519588366, 4.2119885938455015, 1.6073265899384204, 0.05 +3.098082544645826, 4.274783853739785, 1.2559051978856672, 0.05 +3.314097522079869, 4.320299548680862, 0.910313898821542, 0.05 +3.5315341475730757, 4.348732509864138, 0.568659223665513, 0.05 +3.749542579323742, 4.360168635013317, 0.22872250298359376, 0.05 +3.9677459237594244, 4.3640668887136504, 0.07796507400666286, 0.05 +4.186237970001418, 4.369840924839875, 0.11548072252448804, 0.05 +4.405107935179111, 4.377399303553857, 0.151167574279647, 0.05 +4.624439057076714, 4.38662243795205, 0.18446268796385112, 0.05 +4.844307437669154, 4.3973676118487965, 0.2149034779349357, 0.05 +5.064781169497488, 4.409474636566687, 0.24214049435780538, 0.05 +5.285919757203556, 4.422771754121344, 0.2659423510931447, 0.05 +5.507773828085872, 4.43708141764633, 0.28619327049971943, 0.05 +5.7303851099654155, 4.452225637590872, 0.3028843988908392, 0.05 +5.953786643038549, 4.468030661462666, 0.31610047743587444, 0.05 +6.178003185057729, 4.484330840383591, 0.3260035784185078, 0.05 +6.402910253358908, 4.498141366023587, 0.27621051279991704, 0.05 +6.627882219192085, 4.499439316663545, 0.025959012799159353, 0.05 +6.8519264776864395, 4.4808851698870775, -0.3710829355293477, 0.05 +7.074030589347931, 4.442082233229836, -0.7760587331448221, 0.05 +7.293163911953531, 4.382666452111999, -1.1883156223567504, 0.05 +7.5082796016046585, 4.30231379302254, -1.6070531817891798, 0.05 +7.718316829891096, 4.200744565728742, -2.0313845458759516, 0.05 +7.922203088725012, 4.077725176678312, -2.460387781008606, 0.05 +8.118856482478455, 3.9330678750688697, -2.893146032188847, 0.05 +8.30718793708578, 3.7666290921465304, -3.3287756584467854, 0.05 +8.486249410428545, 3.5812294668553015, -3.7079925058245777, 0.05 +8.655598265512637, 3.386977101681845, -3.885047303469129, 0.05 +8.815157219655921, 3.1911790828656863, -3.9159603763231754, 0.05 +8.964855903378185, 2.9939736744452663, -3.9441081684084, 0.05 +9.104630516129816, 2.795492255032633, -3.969628388252664, 0.05 +9.23442345797141, 2.595858836831873, -3.992668364015204, 0.05 +9.35418295704714, 2.395189981514606, -4.013377106345342, 0.05 +9.463862708065413, 2.193595020365473, -4.031899222982656, 0.05 +9.563421529796505, 1.9911764346218497, -4.048371714872467, 0.05 +9.652823049031893, 1.7880303847077552, -4.062920998281889, 0.05 +9.732035412796836, 1.584247275298878, -4.075662188177542, 0.05 +9.80103103176678, 1.3799123793988544, -4.086697918000475, 0.05 +9.85978635488024, 1.1751064622692275, -4.096118342592536, 0.05 +9.908430312919776, 0.9728791607907019, -4.044546029570513, 0.05 +9.94761077233237, 0.7836091882518653, -3.785399450776732, 0.05 +9.978346296734847, 0.6147104880495352, -3.377974004046602, 0.05 +10.00165931755646, 0.4662604164322493, -2.969001432345718, 0.05 +10.018575212730813, 0.33831790348705576, -2.558850258903871, 0.05 +10.030121528672876, 0.2309263188412466, -2.147831692916183, 0.05 +10.037327332171778, 0.14411606997805232, -1.7362049772638855, 0.05 +10.041222684924294, 0.07790705505035164, -1.3241802985540134, 0.05 +10.042838233847936, 0.03231097847282725, -0.9119215315504878, 0.05 +10.04320491371034, 0.007333597248086813, -0.49954762449480866, 0.05 +10.04320491371034, 0.0, -0.14667194496173624, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftRedShootProfile.csv b/RoboRIO/src/main/resources/calciferLeftRedShootProfile.csv index 93d4b960..3849b839 100644 --- a/RoboRIO/src/main/resources/calciferLeftRedShootProfile.csv +++ b/RoboRIO/src/main/resources/calciferLeftRedShootProfile.csv @@ -1,71 +1,61 @@ -70 -3.741170593125583E-4, 0.014964682372502331, 0.05, -0.0021817787357194672, 0.03615323352813818, 0.05, -0.006248954321584508, 0.08134351171730081, 0.05, -0.013479268289459114, 0.1446062793574921, 0.05, -0.024776050361409, 0.22593564143899772, 0.05, -0.041042104717452205, 0.325321087120864, 0.05, -0.06317935715035805, 0.4427450486581169, 0.05, -0.09208831739758679, 0.5781792049445748, 0.05, -0.12866726739669562, 0.7315789999821766, 0.05, -0.17381105581490475, 0.9028757683641826, 0.05, -0.22795824447760574, 1.0829437732540197, 0.05, -0.2910902670119474, 1.2626404506868334, 0.05, -0.36318155613964936, 1.4418257825540393, 0.05, -0.4441978112176374, 1.6203251015597604, 0.05, -0.5340941041060592, 1.7979258577684347, 0.05, -0.6328128873999003, 1.9743756658768212, 0.05, -0.7402819911243207, 2.149382074488409, 0.05, -0.8564127177881924, 2.3226145332774344, 0.05, -0.9810981635336778, 2.4937089149097083, 0.05, -1.1142119072476164, 2.662274874278772, 0.05, -1.2556072073583207, 2.8279060022140867, 0.05, -1.4051168306505066, 2.990192465843722, 0.05, -1.5625535999080886, 3.148735385151639, 0.05, -1.7277116916467177, 3.3031618347725824, 0.05, -1.9003686427393411, 3.453139021852467, 0.05, -2.079861284697328, 3.589852839159735, 0.05, -2.265106920993762, 3.7049127259286774, 0.05, -2.455047052440478, 3.79880262893432, 0.05, -2.64865374559045, 3.8721338629994406, 0.05, -2.8449343006267718, 3.9256111007264307, 0.05, -3.042934104401667, 3.9599960754979104, 0.05, -3.2417377805081404, 3.976073522129469, 0.05, -3.440468919568526, 3.9746227812077097, 0.05, -3.638288771323393, 3.9563970350973414, 0.05, -3.834371343485069, 3.9216514432335146, 0.05, -4.02792515235872, 3.8710761774730305, 0.05, -4.218213519784704, 3.8057673485196797, 0.05, -4.404529205703735, 3.726313718380627, 0.05, -4.586192862702973, 3.633273139984755, 0.05, -4.762551863629965, 3.5271800185398496, 0.05, -4.932979431303197, 3.40855135346464, 0.05, -5.096873934556353, 3.2778900650631053, 0.05, -5.253658169758888, 3.135684704050721, 0.05, -5.402778423963895, 2.982405084100118, 0.05, -5.54372381971687, 2.8189079150595107, 0.05, -5.676351392574336, 2.6525514571493063, 0.05, -5.800847920787315, 2.4899305642595757, 0.05, -5.917392472140184, 2.3308910270573926, 0.05, -6.026156204596789, 2.175274649132093, 0.05, -6.1273019900557, 2.0229157091782133, 0.05, -6.2209839303032854, 1.8736388049517219, 0.05, -6.307346830923964, 1.7272580124135832, 0.05, -6.3865256908953585, 1.5835771994278893, 0.05, -6.458645254251559, 1.442391267124016, 0.05, -6.523819656740687, 1.3034880497825618, 0.05, -6.582152186230929, 1.1666505898048358, 0.05, -6.6337351620341805, 1.0316595160650326, 0.05, -6.678649926370078, 0.8982952867179473, 0.05, -6.716966931654855, 0.7663401056955377, 0.05, -6.748764805414679, 0.6359574751964877, 0.05, -6.774432019810552, 0.5133442879174593, 0.05, -6.794645891492005, 0.4042774336290525, 0.05, -6.810071790209492, 0.3085179743497593, 0.05, -6.821365889277678, 0.22588198136372475, 0.05, -6.829177520368228, 0.1562326218110017, 0.05, -6.834151152917487, 0.09947265098518054, 0.05, -6.8369280167951745, 0.05553727755374575, 0.05, -6.838147383100922, 0.02438732611495123, 0.05, -6.83844751355303, 0.00600260904216607, 0.05, -6.83844751355303, 0.0, 0.05, +60 +5.571761821131456E-4, 0.022287047284525824, 0.4457409456905165, 0.05 +0.0032325893677627024, 0.05350826371299113, 0.6244243285693061, 0.05 +0.009252111334715322, 0.12039043933905237, 1.337643512521225, 0.05 +0.019952931786456234, 0.21401640903481825, 1.8725193939153175, 0.05 +0.03667149334196884, 0.3343712311102522, 2.4070964415086786, 0.05 +0.06074288760842538, 0.4814278853291308, 2.941133084377572, 0.05 +0.09349990757959509, 0.6551403994233941, 3.474250281885266, 0.05 +0.1362715710500687, 0.8554332694094724, 4.005857399721566, 0.05 +0.19038085160844836, 1.0821856111675932, 4.535046835162415, 0.05 +0.257141266414601, 1.3352082961230523, 5.060453699109182, 0.05 +0.3371852015320185, 1.6008787023483497, 5.3134081245059495, 0.05 +0.4304613589803245, 1.8655231489661201, 5.2928889323554085, 0.05 +0.5368986414304665, 2.12874564900284, 5.264450000734393, 0.05 +0.6564014804113434, 2.3900567796175367, 5.226222612293938, 0.05 +0.7888450557429227, 2.648871506631588, 5.176294540281026, 0.05 +0.9340707653055479, 2.904514191252503, 5.1128536924183, 0.05 +1.0918823817555896, 3.1562323290008334, 5.034362754966608, 0.05 +1.2620433741611574, 3.4032198481113562, 4.939750382210457, 0.05 +1.4442758490109942, 3.644649496996734, 4.828592977707551, 0.05 +1.6382614563961442, 3.879712147702999, 4.701253014125308, 0.05 +1.8430051715317746, 4.094874302712607, 4.303243100192153, 0.05 +2.056868377506385, 4.277264119492209, 3.6477963355920373, 0.05 +2.2782383195174716, 4.427398840221728, 3.0026944145903833, 0.05 +2.5055432865691585, 4.54609934103374, 2.3740100162402378, 0.05 +2.737264759449558, 4.6344294576079905, 1.7666023314850143, 0.05 +2.9719456634631674, 4.693618080272182, 1.1837724532838223, 0.05 +3.208194576456215, 4.72497825986095, 0.6272035917753627, 0.05 +3.4446863625045907, 4.729835720967517, 0.09714922213134969, 0.05 +3.6801601108024786, 4.709474965957756, -0.40721510019523066, 0.05 +3.9133057014549615, 4.662911813049655, -0.9312630581620063, 0.05 +4.142874395118047, 4.5913738732616975, -1.4307587957591572, 0.05 +4.367781527220974, 4.4981426420585615, -1.8646246240627207, 0.05 +4.58699046719992, 4.384178799578905, -2.279276849593135, 0.05 +4.799509855158807, 4.2503877591777535, -2.675820808023026, 0.05 +5.004391684478107, 4.0976365863859865, -3.0550234558353395, 0.05 +5.200729962644302, 3.926765563323889, -3.417420461241951, 0.05 +5.3876595281836925, 3.738591310787819, -3.763485050721398, 0.05 +5.564354516053379, 3.533899757393733, -4.093831067881721, 0.05 +5.730025954278246, 3.3134287644973326, -4.4094198579280075, 0.05 +5.884015951032808, 3.0797999350912266, -4.672576588122119, 0.05 +6.026203049290736, 2.8437419651585576, -4.721159398653381, 0.05 +6.156877063091782, 2.613480276020937, -4.605233782752416, 0.05 +6.2763101363728735, 2.3886614656218175, -4.496376207982387, 0.05 +6.384755627833958, 2.1689098292216893, -4.395032728002564, 0.05 +6.482446938583373, 1.9538262149883052, -4.301672284667681, 0.05 +6.569596455073783, 1.7429903298081901, -4.216717703602302, 0.05 +6.646394728892468, 1.5359654763737, -4.140497068689801, 0.05 +6.713009959073658, 1.332304603623809, -4.0732174549978195, 0.05 +6.769587789263467, 1.1315566037961609, -4.014959996552965, 0.05 +6.81634303475918, 0.9351049099142651, -3.9290338776379152, 0.05 +6.8539501689762, 0.7521426843404073, -3.6592445114771555, 0.05 +6.883448136832523, 0.5899593571264544, -3.243666544279058, 0.05 +6.905851425723556, 0.4480657778206655, -2.837871586115779, 0.05 +6.92215579022411, 0.3260872900110851, -2.439569756191607, 0.05 +6.93334313908418, 0.22374697720139589, -2.046806256193784, 0.05 +6.94038562223649, 0.1408496630461877, -1.6579462831041636, 0.05 +6.944248958543059, 0.07726672613137558, -1.2716587382962423, 0.05 +6.945895039488403, 0.032921618906875165, -0.8869021444900084, 0.05 +6.946283834292208, 0.007775896076096069, -0.5029144566155819, 0.05 +6.946283834292208, 0.0, -0.15551792152192137, 0.05 diff --git a/RoboRIO/src/main/resources/calciferLeftforward100InProfile.csv b/RoboRIO/src/main/resources/calciferLeftforward100InProfile.csv new file mode 100644 index 00000000..5206ca4a --- /dev/null +++ b/RoboRIO/src/main/resources/calciferLeftforward100InProfile.csv @@ -0,0 +1,68 @@ +67 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0027173913043478243, 0.04347826086956518, 0.43478260869565144, 0.05 +0.007608695652173899, 0.09782608695652148, 1.086956521739126, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.02989130434782601, 0.2717391304347819, 1.956521739130429, 0.05 +0.04945652173913106, 0.3913043478261009, 2.3913043478263805, 0.05 +0.07608695652174083, 0.5326086956521955, 2.8260869565218916, 0.05 +0.1108695652173944, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783097, 0.8804347826087313, 3.6956521739132, 0.05 +0.2092391304347897, 1.0869565217391746, 4.130434782608865, 0.05 +0.2744565217391353, 1.3043478260869124, 4.347826086954756, 0.05 +0.35054347826085114, 1.5217391304343164, 4.347826086948081, 0.05 +0.437499999999955, 1.7391304347820769, 4.347826086955209, 0.05 +0.5353260869564568, 1.956521739130036, 4.347826086959183, 0.05 +0.644021739130412, 2.1739130434791054, 4.347826086981388, 0.05 +0.7635869565217627, 2.3913043478270124, 4.34782608695814, 0.05 +0.894021739130509, 2.608695652174926, 4.347826086958273, 0.05 +1.0353260869566507, 2.826086956522833, 4.34782608695814, 0.05 +1.1874999999999856, 3.0434782608666966, 4.347826086877271, 0.05 +1.3505434782606922, 3.260869565214133, 4.347826086948725, 0.05 +1.524456521738779, 3.478260869561738, 4.3478260869521, 0.05 +1.7092391304342465, 3.6956521739093473, 4.347826086952189, 0.05 +1.9048913043470945, 3.913043478256961, 4.347826086952278, 0.05 +2.1108695652164533, 4.1195652173871755, 4.130434782604286, 0.05 +2.326086956520586, 4.304347826082653, 3.695652173909547, 0.05 +2.549456521737754, 4.467391304343362, 3.260869565214186, 0.05 +2.7798913043462194, 4.608695652169308, 2.826086956518914, 0.05 +3.0163043478242435, 4.728260869560481, 2.391304347823464, 0.05 +3.257608695650089, 4.826086956516908, 1.9565217391285472, 0.05 +3.502717391302018, 4.902173913038581, 1.5217391304334527, 0.05 +3.750543478258292, 4.956521739125481, 1.0869565217380028, 0.05 +3.9999999999971734, 4.989130434777627, 0.6521739130429083, 0.05 +4.249999999997386, 5.000000000004254, 0.21739130453255484, 0.05 +4.499637862317328, 4.992757246398831, -0.14485507210846293, 0.05 +4.748007971014006, 4.967402173933575, -0.5071014493051251, 0.05 +4.994023369565676, 4.920307971033395, -0.9418840580035948, 0.05 +5.236597101450595, 4.851474637698381, -1.376666666700288, 0.05 +5.474642210147018, 4.760902173928461, -1.8114492753984024, 0.05 +5.707071739133202, 4.64859057972367, -2.246231884095806, 0.05 +5.9327987318874, 4.514539855083957, -2.681014492794276, 0.05 +6.150736231887871, 4.358750000009426, -3.115797101490614, 0.05 +6.35979728261287, 4.1812210144999895, -3.550579710188728, 0.05 +6.558894927540653, 3.9819528985556474, -3.9853623188868426, 0.05 +6.747304347830671, 3.768188405800359, -4.275289855105768, 0.05 +6.924844202903249, 3.5507971014515682, -4.3478260869758145, 0.05 +7.091514492758385, 3.333405797102724, -4.34782608697688, 0.05 +7.247315217396082, 3.1160144927539335, -4.3478260869758145, 0.05 +7.3922463768163365, 2.8986231884050895, -4.34782608697688, 0.05 +7.526307971019151, 2.6812318840562988, -4.3478260869758145, 0.05 +7.649500000004525, 2.4638405797074725, -4.347826086976525, 0.05 +7.761822463772457, 2.2464492753586462, -4.347826086976525, 0.05 +7.86327536232295, 2.0290579710098555, -4.3478260869758145, 0.05 +7.953858695656001, 1.8116666666610115, -4.34782608697688, 0.05 +8.033572463771613, 1.5942753623122208, -4.3478260869758145, 0.05 +8.102416666669784, 1.37688405796343, -4.3478260869758145, 0.05 +8.160391304350512, 1.1594927536145505, -4.347826086977591, 0.05 +8.207858514494996, 0.9493442028896837, -4.2029710144973365, 0.05 +8.245723913045303, 0.7573079710061492, -3.8407246376706894, 0.05 +8.275074456523177, 0.5870108695574672, -3.405942028973641, 0.05 +8.29699710145036, 0.4384528985436731, -2.9711594202758818, 0.05 +8.3125788043486, 0.3116340579648025, -2.536376811577412, 0.05 +8.322906521739638, 0.20655434782074877, -2.101594202881074, 0.05 +8.32906721014522, 0.12321376811165408, -1.666811594181894, 0.05 +8.33214782608709, 0.06161231883737628, -1.232028985485556, 0.05 +8.33323532608699, 0.021749999998021963, -0.7972463767870863, 0.05 +8.333416666666666, 0.003626811593520074, -0.3624637680900378, 0.05 +8.333416666666666, 0.0, -0.07253623187040148, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueBackupProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueBackupProfile.csv index 255d8e23..96e3c2c0 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueBackupProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueBackupProfile.csv @@ -1,55 +1,49 @@ -54 -3.6998202195815923E-4, 0.014799280878326368, 0.05, -0.002039961642815431, 0.033399592417145435, 0.05, -0.005794962153935641, 0.0751000102224042, 0.05, -0.012462141029413364, 0.13334357750955445, 0.05, -0.022858188321339408, 0.20792094583852083, 0.05, -0.037782761500984904, 0.29849146359290996, 0.05, -0.05801043251177683, 0.4045534202158385, 0.05, -0.08428127613196419, 0.5254168724037472, 0.05, -0.11729025103588142, 0.6601794980783444, 0.05, -0.15767551546009037, 0.8077052884841788, 0.05, -0.20560871534191816, 0.958663997636556, 0.05, -0.26080922041149873, 1.104010101391611, 0.05, -0.3229541809588901, 1.2428992109478276, 0.05, -0.39167832454244644, 1.3744828716711266, 0.05, -0.4665720462774402, 1.4978744346998745, 0.05, -0.54717712107955, 1.612101496042196, 0.05, -0.6329793042241456, 1.7160436628919136, 0.05, -0.7230544000222195, 1.8015019159614787, 0.05, -0.8161083094678607, 1.8610781889128227, 0.05, -0.9108478044048207, 1.8947898987392, 0.05, -1.0059814018462143, 1.9026719488278705, 0.05, -1.1002241671062811, 1.8848553052013364, 0.05, -1.1923105664412708, 1.8417279866997929, 0.05, -1.2810203420943151, 1.7741955130608862, 0.05, -1.365222680421039, 1.684046766534476, 0.05, -1.4439426087478766, 1.5743985665367526, 0.05, -1.516402584892606, 1.4491995228945875, 0.05, -1.5821849207234633, 1.315646716617146, 0.05, -1.6413529714920867, 1.1833610153724667, 0.05, -1.6944282905318258, 1.0615063807947813, 0.05, -1.742337075356246, 0.9581756964884016, 0.05, -1.7862589593287233, 0.8784376794495441, 0.05, -1.8274067404325165, 0.8229556220758628, 0.05, -1.8668002229282097, 0.787869649913863, 0.05, -1.9051005845300066, 0.7660072320359376, 0.05, -1.942541118851446, 0.7488106864287909, 0.05, -1.978984977453591, 0.728877172042899, 0.05, -2.0141442116269666, 0.7031846834675105, 0.05, -2.047681750749108, 0.6707507824428335, 0.05, -2.0791869208654026, 0.6301034023258868, 0.05, -2.10823425935552, 0.5809467698023493, 0.05, -2.134419854268946, 0.5237118982685205, 0.05, -2.1573816410625595, 0.4592357358722683, 0.05, -2.176856061539902, 0.3894884095468471, 0.05, -2.19284692732943, 0.3198173157905571, 0.05, -2.205588307894297, 0.25482761129733356, 0.05, -2.2153762666284513, 0.19575917468308737, 0.05, -2.2225541139581084, 0.14355694659314008, 0.05, -2.2274998351476145, 0.09891442379012426, 0.05, -2.2306156750128583, 0.06231679730487495, 0.05, -2.23231974966565, 0.034081493055828804, 0.05, -2.233039549214962, 0.014395990986243237, 0.05, -2.233207226491125, 0.003353545523260657, 0.05, -2.233207226491125, 0.0, 0.05, +48 +5.227250022608844E-4, 0.020909000090435375, 0.41818000180870746, 0.05 +0.002881843550035357, 0.047182370955489446, 0.31089258165197287, 0.05 +0.00818496433981288, 0.10606241579555047, 0.9132990689388265, 0.05 +0.01759602709640648, 0.18822125513187196, 1.2840830140124404, 0.05 +0.03225813354343619, 0.2932421289405943, 1.6632018603923786, 0.05 +0.05328056113476888, 0.4204485518266538, 2.055849901933539, 0.05 +0.08172294470399875, 0.5688476713845974, 2.468354409731648, 0.05 +0.11857694755715203, 0.7370800570630655, 2.9080471549192275, 0.05 +0.16474574741960396, 0.9233759972490385, 3.383134580044842, 0.05 +0.2210215192287427, 1.1255154361827742, 3.902625078561477, 0.05 +0.2875113483817807, 1.32979658306076, 4.277975644105873, 0.05 +0.36366429676493606, 1.5230589676631068, 4.49835917612055, 0.05 +0.4488432031073464, 1.7035781268482066, 4.753229474548593, 0.05 +0.5423179747376319, 1.86949543260571, 5.045258439146316, 0.05 +0.6427543131874434, 2.0087267689962305, 5.160756159125834, 0.05 +0.7482751353943506, 2.110416444138145, 5.07512930683637, 0.05 +0.8569995315771876, 2.1744879236567374, 4.990949418202968, 0.05 +0.9670403896487756, 2.2008171614317606, 4.909141304866278, 0.05 +1.0765058649566095, 2.1893095061566794, 4.829093648099763, 0.05 +1.183513997239142, 2.1401626456506473, 4.744943355109417, 0.05 +1.2862328628313044, 2.0543773118432505, 4.64063200718793, 0.05 +1.3829610405771076, 1.9345635549160605, 4.484015406083985, 0.05 +1.4722614265507683, 1.7860077194732165, 4.221679486249972, 0.05 +1.5528784166550165, 1.6123398020849649, 3.4731761936380146, 0.05 +1.6243354378530523, 1.4291404239607177, 2.41373303731816, 0.05 +1.687268904848185, 1.2586693399026552, 1.3236979007624328, 0.05 +1.743051213046253, 1.1156461639613575, -0.05997025501482511, 0.05 +1.7935267525704703, 1.0095107904843483, -1.6319965795059588, 0.05 +1.8405823369898338, 0.9411116883872703, -3.2211031390501965, 0.05 +1.8857089902595479, 0.9025330653942829, -4.652509188798, 0.05 +1.9297180778979721, 0.8801817527684859, -5.812878465703513, 0.05 +1.9726778976403054, 0.8591963948466678, -6.6767387571687475, 0.05 +2.0140255445068767, 0.8269529373314284, -7.288561598030308, 0.05 +2.0530077181272928, 0.7796434724083227, -7.410504998013412, 0.05 +2.0889394871871323, 0.7186353811967922, -7.141578006059994, 0.05 +2.12112738425728, 0.6437579414029587, -6.864822742797374, 0.05 +2.1489391481401587, 0.5562352776575682, -6.612368720497228, 0.05 +2.172124330713799, 0.4637036514728106, -6.098537214072697, 0.05 +2.190856911070013, 0.3746516071242726, -5.336181988951347, 0.05 +2.205445789884081, 0.2917775762813636, -4.623501218246933, 0.05 +2.2163020595513876, 0.21712539334613745, -3.951641778516486, 0.05 +2.2239124499030507, 0.1522078070332582, -3.3100059083016817, 0.05 +2.2288170764244803, 0.09809253042859492, -2.6897069093766146, 0.05 +2.231591464430491, 0.05548776012020658, -2.08356293152941, 0.05 +2.2328325598910443, 0.024821909211072753, -1.4859834109169339, 0.05 +2.2331484395186605, 0.006317592552326459, -0.8928544191163148, 0.05 +2.2331515200165395, 6.160995758018329E-5, -0.3014611432556367, 0.05 +2.2331515200165395, 0.0, -0.0029682364739050306, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueBoilerToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueBoilerToLoadingProfile.csv index d6e08034..c6724754 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueBoilerToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueBoilerToLoadingProfile.csv @@ -1,148 +1,152 @@ -147 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002777777777777774, 0.04444444444444436, 0.05, -0.007777777777777759, 0.0999999999999997, 0.05, -0.016666666666666625, 0.1777777777777773, 0.05, -0.03055555555555596, 0.27777777777778667, 0.05, -0.05055555555555677, 0.40000000000001623, 0.05, -0.07777777777778011, 0.5444444444444668, 0.05, -0.1133333333333371, 0.7111111111111398, 0.05, -0.1583333333333382, 0.9000000000000221, 0.05, -0.21388888888887678, 1.1111111111107712, 0.05, -0.280555555555523, 1.3333333333329238, 0.05, -0.3583333333333088, 1.5555555555557166, 0.05, -0.4472222222222322, 1.7777777777784676, 0.05, -0.5472222222222709, 2.0000000000007745, 0.05, -0.6583333333333788, 2.222222222222159, 0.05, -0.780555555555479, 2.444444444442002, 0.05, -0.9138888888886788, 2.666666666663997, 0.05, -1.0583333333329787, 2.8888888888859965, 0.05, -1.2138888888883792, 3.111111111108009, 0.05, -1.380555555554879, 3.3333333333299953, 0.05, -1.558333333332479, 3.555555555551999, 0.05, -1.7472222222211788, 3.7777777777739985, 0.05, -1.947222222220979, 3.9999999999960023, 0.05, -2.1583333333318793, 4.222222222218002, 0.05, -2.380555555553879, 4.444444444439997, 0.05, -2.6138888888876117, 4.666666666674653, 0.05, -2.8583333333331686, 4.888888888911138, 0.05, -3.113333333334329, 5.100000000023206, 0.05, -3.3777777777799773, 5.288888888912968, 0.05, -3.6505555555589964, 5.45555555558038, 0.05, -3.9305555555602707, 5.600000000025487, 0.05, -4.216666666672683, 5.722222222248261, 0.05, -4.507777777785119, 5.822222222248712, 0.05, -4.802777777786462, 5.900000000026857, 0.05, -5.090773382796867, 5.759912100208103, 0.05, -5.361298023958856, 5.410492823239794, 0.05, -5.6313867263565145, 5.401774047953168, 0.05, -5.900577760723902, 5.383820687347749, 0.05, -6.168926659411171, 5.366977973745374, 0.05, -6.436504215478969, 5.351551121355966, 0.05, -6.703396779926798, 5.3378512889565854, 0.05, -6.969705996032305, 5.326184322110135, 0.05, -7.235547891482547, 5.316837909004844, 0.05, -7.501051292310884, 5.31006801656675, 0.05, -7.766355578640777, 5.30608572659785, 0.05, -8.031607851538146, 5.305045457947378, 0.05, -8.296959651794003, 5.307036005117124, 0.05, -8.562563411967313, 5.3120752034661765, 0.05, -8.828568850132475, 5.320108763303251, 0.05, -9.095119531977247, 5.331013636895433, 0.05, -9.362349796089841, 5.344605282251904, 0.05, -9.630382210158787, 5.360648281378928, 0.05, -9.899325662429128, 5.378869045406806, 0.05, -10.169274138533789, 5.398969522093213, 0.05, -10.44030617235753, 5.420640676474836, 0.05, -10.712484913212421, 5.443574817097829, 0.05, -10.985858716047995, 5.467476056711452, 0.05, -11.260462142139174, 5.492068521823585, 0.05, -11.536317252572445, 5.517102208665428, 0.05, -11.813435081871166, 5.542356585974424, 0.05, -12.091817194190474, 5.5676422463861535, 0.05, -12.37145724037263, 5.592800923643108, 0.05, -12.652342455335242, 5.617704299252241, 0.05, -12.934455052799663, 5.642251949288424, 0.05, -13.217773490199384, 5.666368747994418, 0.05, -13.502273591237042, 5.690002020753155, 0.05, -13.78792952308542, 5.713118636967582, 0.05, -14.074714631411215, 5.735702166515877, 0.05, -14.36260214505283, 5.757750272832296, 0.05, -14.651565760220816, 5.779272303359749, 0.05, -14.941580119244023, 5.800287180464143, 0.05, -15.232621198436687, 5.820821583853283, 0.05, -15.524666617185195, 5.840908374970146, 0.05, -15.817695882129751, 5.860585298891106, 0.05, -16.111690577353023, 5.879893904465477, 0.05, -16.406634510076753, 5.898878654474553, 0.05, -16.702513821180922, 5.917586222083413, 0.05, -16.99931706707482, 5.936064917877964, 0.05, -17.297035279521072, 5.954364248925062, 0.05, -17.595662006957227, 5.972534548723121, 0.05, -17.89519334193264, 5.99062669950824, 0.05, -18.19562793647549, 6.008691890857022, 0.05, -18.496967007051524, 6.026781411520659, 0.05, -18.799214329632232, 6.044946451614186, 0.05, -19.102376224203464, 6.063237891424618, 0.05, -19.4064615276838, 6.08170606960667, 0.05, -19.711481552446354, 6.100400495251119, 0.05, -20.017450027201257, 6.119369495098006, 0.05, -20.324383015394876, 6.138659763872366, 0.05, -20.63229880579046, 6.158315807911665, 0.05, -20.9412177675305, 6.178379234800794, 0.05, -21.251162161995644, 6.198887889302906, 0.05, -21.562155899933718, 6.219874758761434, 0.05, -21.87422423512481, 6.241366703821843, 0.05, -22.18739338014866, 6.263382900476972, 0.05, -22.50169003035551, 6.28593300413698, 0.05, -22.817140784781774, 6.309015088525336, 0.05, -23.133771446295, 6.332613230264512, 0.05, -23.451606192904418, 6.356694932188375, 0.05, -23.770666606342704, 6.381208268765703, 0.05, -24.09097055713476, 6.40607901584112, 0.05, -24.412530946450588, 6.431207786316517, 0.05, -24.735354318178736, 6.456467434562951, 0.05, -25.05943936783275, 6.481700993080232, 0.05, -25.384775389915948, 6.506720441663957, 0.05, -25.71134072448226, 6.531306691326242, 0.05, -26.039101282283838, 6.555211156031602, 0.05, -26.368009246827548, 6.578159290874231, 0.05, -26.698002064124886, 6.599856345946755, 0.05, -27.028615021973167, 6.612259156965654, 0.05, -27.358748583149836, 6.602671223533375, 0.05, -27.687052094478695, 6.566070226577151, 0.05, -28.012155432474692, 6.50206675991998, 0.05, -28.332676350444235, 6.410418359390847, 0.05, -28.647228566198013, 6.291044315075581, 0.05, -28.9544299126466, 6.1440269289717175, 0.05, -29.25290985365026, 5.969598820073205, 0.05, -29.541315768429822, 5.76811829559123, 0.05, -29.81831757775635, 5.540036186530548, 0.05, -30.083000609015013, 5.293660625173275, 0.05, -30.335093445490703, 5.041856729513827, 0.05, -30.57457398662709, 4.789610822727759, 0.05, -30.801436978939684, 4.537259846251889, 0.05, -31.015690802284475, 4.2850764668958226, 0.05, -31.217354453197455, 4.033273018259608, 0.05, -31.406454835207573, 3.782007640202343, 0.05, -31.583024379972322, 3.531390895294965, 0.05, -31.747099030456628, 3.2814930096860975, 0.05, -31.898716548718077, 3.032350365229, 0.05, -32.037915139668414, 2.7839718190066574, 0.05, -32.16473234488106, 2.5363441042529375, 0.05, -32.27920417022131, 2.2894365068051243, 0.05, -32.38136440946084, 2.0432047847906096, 0.05, -32.471244127160176, 1.797594353986618, 0.05, -32.548871273737376, 1.552542931544051, 0.05, -32.61427039809567, 1.3079824871658856, 0.05, -32.66784590977825, 1.071510233651564, 0.05, -32.71060615417872, 0.8552048880093305, 0.05, -32.74377961190525, 0.6634691545307068, 0.05, -32.76859069012284, 0.49622156435171666, 0.05, -32.78626065745738, 0.35339934669081047, 0.05, -32.79800847851208, 0.23495642109396978, 0.05, -32.80505151488082, 0.1408607273748006, 0.05, -32.808606105427174, 0.0710918109270342, 0.05, -32.80988801339627, 0.0256381593818532, 0.05, -32.81011274400287, 0.004494612132042596, 0.05, -32.81011274400287, 0.0, 0.05, +151 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002717391304347822, 0.04347826086956514, 0.4347826086956506, 0.05 +0.007608695652173897, 0.09782608695652148, 1.0869565217391268, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.029891304347826463, 0.27173913043479087, 1.956521739130609, 0.05 +0.04945652173913161, 0.391304347826103, 2.391304347826243, 0.05 +0.07608695652174138, 0.5326086956521955, 2.8260869565218494, 0.05 +0.11086956521739495, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783155, 0.8804347826087319, 3.695652173913211, 0.05 +0.20923913043477188, 1.0869565217388066, 4.130434782601495, 0.05 +0.27445652173909973, 1.304347826086557, 4.347826086955009, 0.05 +0.350543478260842, 1.5217391304348449, 4.347826086965756, 0.05 +0.4375000000000061, 1.7391304347832826, 4.3478260869687535, 0.05 +0.5353260869565658, 1.956521739131194, 4.347826086958229, 0.05 +0.6440217391304945, 2.1739130434785747, 4.347826086947615, 0.05 +0.7635869565216794, 2.3913043478236973, 4.347826086902451, 0.05 +0.8940217391302444, 2.6086956521713, 4.347826086952056, 0.05 +1.0353260869561902, 2.826086956518914, 4.347826086952278, 0.05 +1.1874999999995164, 3.0434782608665234, 4.347826086952189, 0.05 +1.350543478260223, 3.260869565214133, 4.347826086952189, 0.05 +1.5244565217383097, 3.4782608695617334, 4.347826086952011, 0.05 +1.709239130433777, 3.6956521739093473, 4.347826086952278, 0.05 +1.904891304346625, 3.9130434782569568, 4.347826086952189, 0.05 +2.1108695652159843, 4.119565217387184, 4.130434782604553, 0.05 +2.3260869565201174, 4.304347826082662, 3.695652173909547, 0.05 +2.5494565217375595, 4.467391304348842, 3.2608695653236097, 0.05 +2.779891304347304, 4.608695652194887, 2.8260869569209035, 0.05 +3.016304347826641, 4.7282608695867445, 2.391304347837142, 0.05 +3.257608695653826, 4.826086956543696, 1.9565217391390277, 0.05 +3.5027173913071152, 4.902173913065786, 1.5217391304418015, 0.05 +3.7505434782647646, 4.956521739152988, 1.0869565217440424, 0.05 +4.000000000005031, 4.989130434805329, 0.6521739130468163, 0.05 +4.2500000000061675, 5.000000000022737, 0.217391304348169, 0.05 +4.500000000007306, 5.000000000022773, 7.105427357601002E-13, 0.05 +4.750000000008443, 5.000000000022737, -7.105427357601002E-13, 0.05 +5.000000000009582, 5.000000000022773, 7.105427357601002E-13, 0.05 +5.22241254735571, 4.448250946922575, 10.787819820599278, 0.05 +5.443753129219028, 4.426811637266355, 0.6701176685793264, 0.05 +5.663725447614075, 4.399446367900928, 0.5467360913308639, 0.05 +5.882309874689655, 4.371688541511594, 0.5545504541471225, 0.05 +6.099501870787017, 4.343839921947236, 0.5563387594866498, 0.05 +6.315315334044061, 4.316269265140888, 0.5507572512310688, 0.05 +6.52978597961773, 4.28941291147339, 0.536462372505877, 0.05 +6.742974484871042, 4.263770105066227, 0.5121980832726614, 0.05 +6.954969099717576, 4.239892296930671, 0.47692204946660155, 0.05 +7.165887374072374, 4.21836548709596, 0.4299475673244224, 0.05 +7.375876637709667, 4.199785272745871, 0.37108247507095626, 0.05 +7.585112929391575, 4.184725833638157, 0.3007571428295641, 0.05 +7.793798167375193, 4.17370475967236, 0.22010049791976627, 0.05 +8.002155535096175, 4.167147354419662, 0.13095473044099748, 0.05 +8.210423261341813, 4.165354524912727, 0.03580367864151057, 0.05 +8.418847185607161, 4.168478485306976, -0.062386879920843796, 0.05 +8.627672685458872, 4.17650999703422, -0.160394410642688, 0.05 +8.837136633162205, 4.18927895406664, -0.25500891530750636, 0.05 +9.047460050328478, 4.206468343325463, -0.3432984838247144, 0.05 +9.258842023412752, 4.2276394616854684, -0.42283413285169047, 0.05 +9.471455262436761, 4.252264780480173, -0.4918421670378592, 0.05 +9.685443467599201, 4.2797641032488105, -0.5492701740438655, 0.05 +9.900920458788285, 4.3095398237816545, -0.5947690951182061, 0.05 +10.117970854678536, 4.341007917805004, -0.6286084499733136, 0.05 +10.336651981586567, 4.373622538160609, -0.6515485266554322, 0.05 +10.556996647366159, 4.406893315591837, -0.6646957299677858, 0.05 +10.779016427492676, 4.440395602530356, -0.6693605391671831, 0.05 +11.002705153882575, 4.473774527797955, -0.6669353920925403, 0.05 +11.228042364881782, 4.506744219984129, -0.6587974234728655, 0.05 +11.454996543649683, 4.539083575358014, -0.6462397854419599, 0.05 +11.68352803829554, 4.570629892917145, -0.6304279239803812, 0.05 +11.91359160643368, 4.601271362762813, -0.6123791607106988, 0.05 +12.14513857347959, 4.630939340918193, -0.5929554287226324, 0.05 +12.378118616845205, 4.659600867312306, -0.5728696970248492, 0.05 +12.612481207447187, 4.687251812039642, -0.5526984376498767, 0.05 +12.848176749848236, 4.713910848020958, -0.5328974329579239, 0.05 +13.08515746429511, 4.73961428893747, -0.5138194750106706, 0.05 +13.32337805330787, 4.764411780255199, -0.49573170746702644, 0.05 +13.562796194511053, 4.788362824063669, -0.47883077739042434, 0.05 +13.803372892529389, 4.81153396036672, -0.4632582328545354, 0.05 +14.0450727231399, 4.833996612210224, -0.4491116867347067, 0.05 +14.287863993905727, 4.855825415316557, -0.43645590071296425, 0.05 +14.531718843903208, 4.8770969999496145, -0.4253308349622742, 0.05 +14.776613298992647, 4.897889101788768, -0.41575903014368976, 0.05 +15.022527297391472, 4.918279967976482, -0.40775083321936023, 0.05 +15.269444696026417, 4.938347972698915, -0.401308989281155, 0.05 +15.517353265919402, 4.958171397859683, -0.3964320925393672, 0.05 +15.766244683638488, 4.97782835438174, -0.393116817503838, 0.05 +16.016114522760976, 4.997396782449781, -0.3913599494731024, 0.05 +16.266962248289513, 5.016954510570769, -0.39115954434853606, 0.05 +16.518791215781498, 5.036579349839717, -0.3925154296751643, 0.05 +16.771608675148144, 5.056349187332916, -0.3954293628931005, 0.05 +17.02542577807913, 5.076342058619709, -0.39990453093659895, 0.05 +17.280257586564314, 5.096636169703728, -0.40594453509744, 0.05 +17.53612307833448, 5.117309835403299, -0.413551812096955, 0.05 +17.79304514339749, 5.138441301260178, -0.42272531809414815, 0.05 +18.051050564343644, 5.160108418923109, -0.4334571974659518, 0.05 +18.31016996933644, 5.1823880998559035, -0.4457290018800464, 0.05 +18.57043774483601, 5.205355509991417, -0.45950638894858287, 0.05 +18.83189189291808, 5.229082961641375, -0.47473206609597085, 0.05 +19.094573810840547, 5.253638358449361, -0.49131842992489183, 0.05 +19.35852796982766, 5.2790831797422015, -0.5091370989719834, 0.05 +19.6238014626555, 5.305469856556793, -0.5280075353871005, 0.05 +19.890443387221403, 5.332838491318069, -0.5476828345378593, 0.05 +20.158504024942225, 5.361212754416443, -0.5678350392298626, 0.05 +20.428033774545135, 5.3905949920581735, -0.5880371710468069, 0.05 +20.69908179579616, 5.420960425020504, -0.6077462755579965, 0.05 +20.971694320710107, 5.452250498278898, -0.62628688395586, 0.05 +21.24591260036683, 5.484365593134466, -0.6428363478158872, 0.05 +21.521770465979486, 5.51715731225312, -0.6564176876231365, 0.05 +21.799291508874045, 5.550420857891194, -0.6659020158185669, 0.05 +22.07848592595327, 5.583888341584486, -0.6700241702534804, 0.05 +22.359347117650344, 5.61722383394151, -0.667421446985017, 0.05 +22.641848197201803, 5.6500215910291915, -0.6566938495811492, 0.05 +22.925938631815825, 5.68180869228041, -0.6364944777442183, 0.05 +23.211541307692077, 5.7120535175250335, -0.6056459176204854, 0.05 +23.498550363159403, 5.740181109346538, -0.5632780281632677, 0.05 +23.78683015393623, 5.765595815536564, -0.5089745400791301, 0.05 +24.07621568773126, 5.787710675900639, -0.44290798416227517, 0.05 +24.366514774768387, 5.805981740742547, -0.365938992079613, 0.05 +24.65751198844645, 5.819944273561268, -0.27965438057377057, 0.05 +24.948508381164817, 5.819927854367288, -0.31949059821897663, 0.05 +25.238159767697205, 5.793027730647766, -0.5359224465610346, 0.05 +25.524955914374633, 5.7359229335485935, -0.801097643203974, 0.05 +25.807405772947074, 5.648997171448816, -1.0739751109837137, 0.05 +26.084052834478193, 5.532941230622348, -1.3607166798135495, 0.05 +26.353486489667173, 5.388673103779561, -1.665877093972492, 0.05 +26.614348632542292, 5.217242857502374, -1.992104007597737, 0.05 +26.865335540055256, 5.019738150259246, -2.3401447273204923, 0.05 +27.105195660248654, 4.797202403867982, -2.709107469450256, 0.05 +27.332724320531828, 4.55057320566347, -3.096863919176336, 0.05 +27.547212262440087, 4.289758838165223, -3.363237128811747, 0.05 +27.74859357909098, 4.027626333017855, -3.452201935951571, 0.05 +27.93697545258283, 3.7676374698370085, -3.495215529050677, 0.05 +28.11246743530203, 3.509839654383992, -3.5391580452153537, 0.05 +28.275177531297174, 3.2542019199028998, -3.5824627813283794, 0.05 +28.42520942193064, 3.0006378126692956, -3.6240231002287704, 0.05 +28.562660594975696, 2.749023460901133, -3.663090601405692, 0.05 +28.687621152660935, 2.499211153704746, -3.699189588973324, 0.05 +28.80017311091687, 2.2510391651187147, -3.7320462676223753, 0.05 +28.90039006456881, 2.004339073038801, -3.761524172638442, 0.05 +28.988337086483305, 1.758940438289869, -3.7875848343510388, 0.05 +29.06407077739129, 1.5146738181597241, -3.810252656137183, 0.05 +29.127639419401373, 1.2713728402016584, -3.8295839180333457, 0.05 +29.179526291601075, 1.0377374439940599, -3.7033103961434177, 0.05 +29.22080794361707, 0.8256330403199577, -3.3795535577670788, 0.05 +29.252711059644152, 0.6380623205416208, -3.0006717219651025, 0.05 +29.27645465900911, 0.4748719872991951, -2.6187178474950557, 0.05 +29.293251983234594, 0.33594648450962666, -2.234452475713342, 0.05 +29.30431209951613, 0.22120232563073958, -1.8485156520362478, 0.05 +29.31084122506184, 0.1305825109141231, -1.4614374646352395, 0.05 +29.31404378607192, 0.06405122020161136, -1.0736429051736944, 0.05 +29.3151232237102, 0.02158875276553844, -0.6854543937919944, 0.05 +29.31528255261118, 0.003186578019631716, -0.29709401900733934, 0.05 +29.31528255261118, 0.0, -0.05144714502436782, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueLeftProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueLeftProfile.csv index 7f21747e..08c5be2d 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueLeftProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueLeftProfile.csv @@ -1,90 +1,78 @@ -89 -3.676470588235294E-4, 0.014705882352941176, 0.05, -0.001720122000372861, 0.02704949883098663, 0.05, -0.004763112523682217, 0.06085981046618712, 0.05, -0.010172606382967707, 0.1081898771857098, 0.05, -0.01862425616072077, 0.16903299555506124, 0.05, -0.030793164391220797, 0.24337816461000059, 0.05, -0.04735361481353944, 0.33120900844637285, 0.05, -0.06897874762446593, 0.43250265621852996, 0.05, -0.09634017793109698, 0.5472286061326207, 0.05, -0.13010755606794058, 0.6753475627368721, 0.05, -0.17061062406684885, 0.8100613599781654, 0.05, -0.21783961412749597, 0.9445798012129427, 0.05, -0.27178307953926006, 1.078869308235282, 0.05, -0.3324278757427812, 1.2128959240704222, 0.05, -0.399759142729382, 1.3466253397320163, 0.05, -0.47376028981707174, 1.480022941753794, 0.05, -0.5544129861565598, 1.61305392678976, 0.05, -0.6416971588789474, 1.745683454447752, 0.05, -0.7355910025801236, 1.8778768740235234, 0.05, -0.836071004240915, 2.009600033215827, 0.05, -0.9431119883927144, 2.1408196830359874, 0.05, -1.0566871891000043, 2.2715040141457985, 0.05, -1.1767683544422394, 2.4016233068447006, 0.05, -1.303325893047453, 2.5311507721042723, 0.05, -1.4363290707063827, 2.660063553178596, 0.05, -1.5757462683786116, 2.788343953444577, 0.05, -1.7215453129230611, 2.9159808908889904, 0.05, -1.8736938931895266, 3.042971605329309, 0.05, -2.0321600740412977, 3.169323617035418, 0.05, -2.1969129218791665, 3.2950569567573793, 0.05, -2.367923252733119, 3.4202066170790495, 0.05, -2.545164512786852, 3.5448252010746555, 0.05, -2.7286137961972057, 3.6689856682070747, 0.05, -2.91825299941776, 3.792784064411089, 0.05, -3.113744043505054, 3.9098208817458766, 0.05, -3.3144330142978586, 4.013779415856093, 0.05, -3.5196786322396836, 4.104912358836501, 0.05, -3.7288523733158754, 4.1834748215238315, 0.05, -3.94133806821273, 4.249713897937098, 0.05, -4.156530939187367, 4.303857419492732, 0.05, -4.373836071300205, 4.34610264225675, 0.05, -4.5926663581206535, 4.376605736408969, 0.05, -4.812440007818915, 4.395472993965228, 0.05, -5.032577736606144, 4.402754575744581, 0.05, -5.2525419370331115, 4.399284008539343, 0.05, -5.471791764039145, 4.384996540120683, 0.05, -5.689738278069272, 4.358930280602535, 0.05, -5.905784103268687, 4.320916503988303, 0.05, -6.119321452049951, 4.270746975625275, 0.05, -6.329730681539189, 4.208184589784778, 0.05, -6.53637941393335, 4.13297464788321, 0.05, -6.738622210070118, 4.04485592273537, 0.05, -6.93580074998438, 3.9435707982852364, 0.05, -7.1272444491847, 3.8288739840063983, 0.05, -7.312558282702054, 3.7062766703470795, 0.05, -7.49167005367015, 3.582235419361932, 0.05, -7.664547058267319, 3.457540091943364, 0.05, -7.83115444246084, 3.33214768387043, 0.05, -7.991456090096668, 3.2060329527165585, 0.05, -8.145415360571636, 3.0791854094993703, 0.05, -8.292995691372633, 2.9516066160199537, 0.05, -8.434161080968552, 2.8233077919183733, 0.05, -8.568876468170913, 2.694307744047207, 0.05, -8.697108024316718, 2.5646311229160976, 0.05, -8.818823371528785, 2.434306944241357, 0.05, -8.933991741219142, 2.3033673938071315, 0.05, -9.042584083197655, 2.1718468395702426, 0.05, -9.144573135778748, 2.039781051621867, 0.05, -9.239933465219849, 1.9072065888220262, 0.05, -9.32864148143267, 1.7741603242564368, 0.05, -9.41067543588441, 1.6406790890348106, 0.05, -9.486015406626112, 1.5067994148340493, 0.05, -9.554643274259663, 1.372557352670996, 0.05, -9.616542692203705, 1.2379883588808371, 0.05, -9.671699053790595, 1.1031272317378151, 0.05, -9.720099458284382, 0.9680080898757359, 0.05, -9.761732677496648, 0.8326643842452941, 0.05, -9.796589124012291, 0.697128930312856, 0.05, -9.824956524901232, 0.5673480177788292, 0.05, -9.84746446552033, 0.4501588123819809, 0.05, -9.864788644099367, 0.34648357158074305, 0.05, -9.87760627182361, 0.2563525544848932, 0.05, -9.886595698288643, 0.17978852930064573, 0.05, -9.89243609379695, 0.11680791016616025, 0.05, -9.89580718464871, 0.06742181703520467, 0.05, -9.89738904204948, 0.03163714801540614, 0.05, -9.897861922081997, 0.009457600650327573, 0.05, -9.897906157249288, 8.847033458236003E-4, 0.05, -9.897906157249288, 0.0, 0.05, +77 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002555019167668077, 0.04023081813597023, 0.4997314150060453, 0.05 +0.007080819548369013, 0.09051600761401872, 1.1682093260444564, 0.05 +0.015126116085535685, 0.1609059307433334, 1.6356796459319756, 0.05 +0.027695428158481274, 0.25138624145891175, 2.1034369987423904, 0.05 +0.045792096820766647, 0.3619333732457074, 2.5716652793640216, 0.05 +0.07041770440654671, 0.49251215171560114, 3.0405964523777538, 0.05 +0.10257137005940782, 0.6430733130572222, 3.5105121544297746, 0.05 +0.14324891429446138, 0.8135508847010711, 3.981745751942183, 0.05 +0.19344188574201782, 1.0038594289511287, 4.454685967100993, 0.05 +0.25363500833262626, 1.2038624518121688, 4.695571699134136, 0.05 +0.3238069889442045, 1.403439612231565, 4.704080066624057, 0.05 +0.4039327289691339, 1.6025148004985883, 4.7141087476893695, 0.05 +0.4939832213717279, 1.8010098480518792, 4.72569854509342, 0.05 +0.5939254462017101, 1.9988444965996435, 4.738890612525601, 0.05 +0.7037222730237491, 2.1959365364407812, 4.753723870004354, 0.05 +0.8233323790956599, 2.392202121438217, 4.77023045341606, 0.05 +0.952710196966259, 2.5875563574119824, 4.788430719309806, 0.05 +1.0918059084251344, 2.7819142291775067, 4.808326389167474, 0.05 +1.240565506791416, 2.975191967325633, 4.829891895390492, 0.05 +1.3989309547600475, 3.167308959372629, 4.8530631509070865, 0.05 +1.5668404728356564, 3.358190361512177, 4.87772408557924, 0.05 +1.744228999646401, 3.547770536214893, 4.903689409078318, 0.05 +1.9305379061877368, 3.7261781308267152, 4.692308040215707, 0.05 +2.1247221861937757, 3.883685600120775, 4.24071430553651, 0.05 +2.325746995407922, 4.02049618428292, 3.785064234681581, 0.05 +2.5325897204098, 4.136854500037564, 3.324532664191615, 0.05 +2.7442418516731077, 4.233042625266155, 2.858372413399195, 0.05 +2.9597105401547346, 4.309373769632538, 2.3859629538497096, 0.05 +3.1780197033585185, 4.366183264075678, 1.9068633158057047, 0.05 +3.398210547726503, 4.403816887359695, 1.4208651065398215, 0.05 +3.6193413916122066, 4.422616877714069, 0.9280390750257261, 0.05 +3.8404867074360585, 4.422906316477038, 0.42876678582237204, 0.05 +4.061214758411386, 4.414561019506552, 0.16673377791381228, 0.05 +4.281581475044782, 4.407334332667934, 0.1443826897084044, 0.05 +4.501647660701352, 4.401323713131383, 0.12008532490421331, 0.05 +4.721478321586324, 4.396613217699442, 0.09410944107628438, 0.05 +4.941141853565952, 4.393270639592554, 0.06677979092703623, 0.05 +5.160709108663971, 4.39134510196038, 0.03846923034647176, 0.05 +5.380252371505671, 4.390865256834006, 0.009586534082988152, 0.05 +5.59984428221639, 4.391838214214376, -0.019438133370162092, 0.05 +5.819556745913994, 4.394249273952082, -0.04816926867036386, 0.05 +6.039459869940862, 4.398062480537363, -0.076182420670321, 0.05 +6.25933396070144, 4.3974818152115525, -0.24881564449762195, 0.05 +6.478474135858947, 4.382803503150124, -0.6621205092131532, 0.05 +6.695972433757934, 4.349965957979743, -1.16840814959696, 0.05 +6.910906617754184, 4.298683679924992, -1.669001340799472, 0.05 +7.1223383487948135, 4.228634620812593, -2.163171512224764, 0.05 +7.329312221020663, 4.139477444516982, -2.6505337325431633, 0.05 +7.530855629795373, 4.030868175494196, -3.131035098586672, 0.05 +7.725979385452628, 3.902475113145101, -3.6049197336332917, 0.05 +7.913678947502198, 3.7539912409914047, -4.072679543684856, 0.05 +8.092936138419807, 3.5851438183521878, -4.534997585452469, 0.05 +8.263014390424866, 3.401565040101173, -4.849416606586487, 0.05 +8.423660496794993, 3.212922127402549, -4.922414914213746, 0.05 +8.574817020561623, 3.023130475332594, -4.899501201736509, 0.05 +8.71642816204279, 2.8322228296233476, -4.8772344185407235, 0.05 +8.848440533195882, 2.6402474230618456, -4.855925177332354, 0.05 +8.970803720706183, 2.447263750206019, -4.835799436594179, 0.05 +9.083470680495365, 2.2533391957836524, -4.817015678625811, 0.05 +9.186398000739706, 2.0585464048868216, -4.799679685004294, 0.05 +9.279546064227256, 1.8629612697510005, -4.783857216134821, 0.05 +9.362879136569505, 1.6666614468449847, -4.769584000030775, 0.05 +9.436365400798005, 1.4697252845699917, -4.756874347811064, 0.05 +9.49997695508624, 1.2722310857647114, -4.745727920891514, 0.05 +9.55368978759559, 1.0742566501870199, -4.736134727414725, 0.05 +9.597782015936325, 0.8818445668146669, -4.586828299872918, 0.05 +9.633034006139438, 0.7050398040622542, -4.203636619692639, 0.05 +9.660430288649014, 0.547925650191507, -3.727888560308903, 0.05 +9.68095929310312, 0.4105800890821242, -3.2536982915616774, 0.05 +9.695612415459573, 0.2930624471290594, -2.7806930390006555, 0.05 +9.70538321834292, 0.19541605766694803, -2.3085538240952976, 0.05 +9.711266762445005, 0.11767088204170933, -1.8370131736669648, 0.05 +9.714259064124546, 0.05984603359081345, -1.365854733474861, 0.05 +9.715356678643397, 0.021952290377027818, -0.8949115960194187, 0.05 +9.71555640615879, 0.003994550307840185, -0.4240664254686264, 0.05 +9.71555640615879, 0.0, -0.09432836055957586, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueLoadingToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueLoadingToLoadingProfile.csv index c6a46998..d7f51b76 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueLoadingToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueLoadingToLoadingProfile.csv @@ -1,130 +1,125 @@ -129 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.0026851747138667693, 0.04259238316622427, 0.05, -0.00747685564132409, 0.09583361854914642, 0.05, -0.01599552892919716, 0.1703734657574614, 0.05, -0.029306288087573993, 0.2662151831675367, 0.05, -0.048474494599516485, 0.3833641302388499, 0.05, -0.07456591127366383, 0.5218283334829467, 0.05, -0.1086468646696288, 0.6816190679192994, 0.05, -0.1517844411351874, 0.8627515293111722, 0.05, -0.20504671679913938, 1.0652455132790393, 0.05, -0.26897029158365865, 1.2784714956903855, 0.05, -0.3435601208764832, 1.4917965858564903, 0.05, -0.428822092849491, 1.705239439460156, 0.05, -0.5247630750663449, 1.918819644337078, 0.05, -0.631390965444012, 2.1325578075533405, 0.05, -0.7487147472474904, 2.346475636069569, 0.05, -0.8767445467621897, 2.560595990293986, 0.05, -1.0154916925732058, 2.77494291622032, 0.05, -1.1649687755350617, 2.989541659237119, 0.05, -1.325189707733075, 3.2044186439602655, 0.05, -1.4961697796557611, 3.419601438453724, 0.05, -1.677925713443894, 3.63511867576266, 0.05, -1.8704757115647341, 3.8509999624167994, 0.05, -2.0738394986060746, 4.067275740826807, 0.05, -2.2880383557964965, 4.283977143808435, 0.05, -2.51309514606787, 4.501135805427472, 0.05, -2.7490343290530297, 4.718783659703191, 0.05, -2.9953451364229378, 4.926216147398165, 0.05, -3.2509793915170135, 5.11268510188152, 0.05, -3.5148867026971216, 5.278146223602162, 0.05, -3.786014014076897, 5.42254622759551, 0.05, -4.0633051891507925, 5.545823501477916, 0.05, -4.345700635821863, 5.647908933421408, 0.05, -4.63213698059304, 5.728726895423535, 0.05, -4.921546797632535, 5.788196340789908, 0.05, -5.212858396918179, 5.826231985712879, 0.05, -5.50499567391355, 5.84274553990741, 0.05, -5.79741981119493, 5.8484827456276145, 0.05, -6.090131913098492, 5.854242038071244, 0.05, -6.383132829367053, 5.860018325371208, 0.05, -6.676423179282015, 5.86580699829924, 0.05, -6.970003375200744, 5.871603918374599, 0.05, -7.263873645445371, 5.877405404892542, 0.05, -7.558034056336522, 5.883208217823013, 0.05, -7.852484533378792, 5.889009540845401, 0.05, -8.14722488149655, 5.89480696235517, 0.05, -8.442254804232055, 5.900598454710113, 0.05, -8.737573921945163, 5.906382354262141, 0.05, -9.033181788940242, 5.912157339901574, 0.05, -9.329077909465108, 5.917922410497307, 0.05, -9.625261752733962, 5.923676865377113, 0.05, -9.921732766744631, 5.929420280213368, 0.05, -10.218490391108158, 5.935152487270548, 0.05, -10.5155340687886, 5.940873553608844, 0.05, -10.81286325679327, 5.946583760093382, 0.05, -11.11047743584548, 5.952283581044197, 0.05, -11.40837611904565, 5.95797366400341, 0.05, -11.706558859554391, 5.963654810174829, 0.05, -12.005025257301561, 5.9693279549434095, 0.05, -12.303774964751895, 5.974994149006688, 0.05, -12.602807691734162, 5.980654539645337, 0.05, -12.902123209366977, 5.986310352656281, 0.05, -13.201721353077119, 5.991962874202859, 0.05, -13.501602024728689, 5.997613433031411, 0.05, -13.801765193869755, 6.003263382821343, 0.05, -14.102210898101326, 6.008914084631405, 0.05, -14.402939242569493, 6.014566889363358, 0.05, -14.703950398579176, 6.020223120193646, 0.05, -15.00524460132283, 6.025884054873085, 0.05, -15.306822146717836, 6.031550907900143, 0.05, -15.60868338734442, 6.037224812531699, 0.05, -15.91082872747341, 6.042906802579784, 0.05, -16.2132586171333, 6.048597793197792, 0.05, -16.51597354526739, 6.0542985626818275, 0.05, -16.818974031896715, 6.060009732586542, 0.05, -17.122260619306925, 6.065731748204206, 0.05, -17.42583386220417, 6.071464857944854, 0.05, -17.72969431688771, 6.077209093670809, 0.05, -18.033842529318683, 6.0829642486194535, 0.05, -18.338279022155852, 6.088729856743389, 0.05, -18.643004280744048, 6.094505171763942, 0.05, -18.94801873796409, 6.1002891444008265, 0.05, -19.25332275804511, 6.106080401620351, 0.05, -19.558916619304473, 6.1118772251872615, 0.05, -19.864800495754352, 6.117677528997555, 0.05, -20.170974437794136, 6.123478840795666, 0.05, -20.477438351811696, 6.129278280351192, 0.05, -20.78419197888475, 6.135072541461068, 0.05, -21.09123487261578, 6.1408578746206155, 0.05, -21.398566376156374, 6.146630070811894, 0.05, -21.70618559858762, 6.152384448624899, 0.05, -22.01400233119454, 6.156334652138368, 0.05, -22.32135477071553, 6.147048790419812, 0.05, -22.627096122509904, 6.114827035887497, 0.05, -22.930075201424945, 6.059581578300819, 0.05, -23.229136591253603, 5.981227796573172, 0.05, -23.52312086533785, 5.87968548168498, 0.05, -23.81086486537881, 5.7548800008191945, 0.05, -24.09120203439743, 5.606743380372363, 0.05, -24.362962797438726, 5.435215260825937, 0.05, -24.624974982351393, 5.240243698253317, 0.05, -24.876154061192274, 5.023581576817606, 0.05, -25.115989550084656, 4.796709777847646, 0.05, -25.344457236581015, 4.569353729927185, 0.05, -25.56153450169778, 4.341545302335266, 0.05, -25.76720030335422, 4.113316033128803, 0.05, -25.961435149990994, 3.8846969327354897, 0.05, -26.144221065124096, 3.655718302662053, 0.05, -26.31554154467443, 3.4264095910066916, 0.05, -26.47538150754086, 3.1967992573285735, 0.05, -26.6237272420528, 2.9669146902388586, 0.05, -26.76056634850118, 2.736782128967551, 0.05, -26.885887680144812, 2.506426632872658, 0.05, -26.999681283520463, 2.2758720675130397, 0.05, -27.101938339331625, 2.045141116223208, 0.05, -27.192651105431665, 1.8142553220007696, 0.05, -27.271812862561667, 1.5832351426000424, 0.05, -27.33941786397862, 1.3521000283390767, 0.05, -27.39555160949026, 1.1226749102327742, 0.05, -27.440879098154078, 0.9065497732763748, 0.05, -27.4765546360837, 0.7135107585925017, 0.05, -27.503733483496465, 0.543576948255255, 0.05, -27.523571628828197, 0.3967629066346158, 0.05, -27.537225598828474, 0.27307940000555414, 0.05, -27.545852299721208, 0.1725340178546392, 0.05, -27.55060888832414, 0.09513177205863277, 0.05, -27.55265267149888, 0.04087566349480605, 0.05, -27.5531410317309, 0.009767204640353718, 0.05, -27.5531410317309, 0.0, 0.05, +124 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0025854119335146455, 0.040838673452901604, 0.48757434569372926, 0.05 +0.00717981334735948, 0.0918880282768967, 1.1529259213810261, 0.05 +0.015347811675516724, 0.16335996656314486, 1.6140395037861806, 0.05 +0.028110754995930413, 0.2552588664082738, 2.075065226146387, 0.05 +0.04649035384097691, 0.36759197690092993, 2.5359459798133863, 0.05 +0.07150886476798882, 0.500370218540238, 2.996607871069936, 0.05 +0.10418932038878234, 0.6536091124158706, 3.4569589456100047, 0.05 +0.1455558112198515, 0.8273298166213833, 3.9168857158158765, 0.05 +0.19663383072956153, 1.0215603901942005, 4.3762504789224765, 0.05 +0.2579397529882631, 1.2261184451740312, 4.604479188820534, 0.05 +0.3294806555745736, 1.4308180517262103, 4.6016437433688795, 0.05 +0.41126509623558843, 1.6356888132202958, 4.59821547401789, 0.05 +0.5033032446275961, 1.8407629678401531, 4.594142169673048, 0.05 +0.6056070258964529, 2.046075625377134, 4.589365932078211, 0.05 +0.7181902758353825, 2.251664998778592, 4.5838252863276985, 0.05 +0.8410689025186089, 2.457572533664528, 4.577455511565667, 0.05 +0.9742610518686563, 2.663842987000947, 4.570190533195486, 0.05 +1.1177872727934457, 2.870524418495787, 4.561964392231994, 0.05 +1.2716706778567195, 3.0776681012654743, 4.552713224028748, 0.05 +1.4359370937656246, 3.2853283181781006, 4.5423767828231565, 0.05 +1.6106151974256944, 3.4935620732013932, 4.530900827119568, 0.05 +1.7957366325723652, 3.702428702933414, 4.518239242911886, 0.05 +1.9908211034895866, 3.9016894183444277, 4.275577233714252, 0.05 +2.1948735772238273, 4.081049474684815, 3.8040355356055677, 0.05 +2.4068970104945158, 4.240468665413767, 3.3333005880931843, 0.05 +2.625891536778161, 4.379890525672905, 2.863696837722234, 0.05 +2.8508536728215144, 4.499242720867072, 2.3955409384730864, 0.05 +3.080775569954887, 4.598437942667453, 1.9291315596786163, 0.05 +3.314644334035373, 4.677375281609722, 1.46473991036828, 0.05 +3.5514414349491807, 4.735942018276155, 1.0026016324441933, 0.05 +3.7901422216008442, 4.774015733033273, 0.5429100585461022, 0.05 +4.029715554408042, 4.791466656143949, 0.08581184303682932, 0.05 +4.269645533788408, 4.798599587607332, -0.14260673364082876, 0.05 +4.509935291292673, 4.805795150085306, -0.14386072893227464, 0.05 +4.750587375968235, 4.813041693511226, -0.144881847801539, 0.05 +4.991603801901597, 4.820328518667256, -0.14568908872812258, 0.05 +5.232986095854485, 4.827645879057751, -0.14630149050667285, 0.05 +5.474735344496593, 4.834984972842165, -0.1467379284442849, 0.05 +5.716852240774151, 4.842337925551161, -0.1470169522051279, 0.05 +5.9593371291356245, 4.84969776722946, -0.14715660118945095, 0.05 +6.202190049148682, 4.857058400261163, -0.14717435210048535, 0.05 +6.445410777445141, 4.864414565929178, -0.14708694347158158, 0.05 +6.688998867652, 4.871761804137171, -0.14691036324139262, 0.05 +6.932953688280093, 4.879096412561862, -0.1466597429739558, 0.05 +7.1772744584264405, 4.886415402926949, -0.14634933627087676, 0.05 +7.4219602811250605, 4.893716453972403, -0.1459925357677072, 0.05 +7.66701017455992, 4.900997868697183, -0.14560175726408886, 0.05 +7.912423100840633, 4.908258525614267, -0.14518856008852055, 0.05 +8.15819799260446, 4.915497835276531, -0.14476354925504253, 0.05 +8.404333777328342, 4.922715694477631, -0.1443364499748867, 0.05 +8.650829399402577, 4.92991244148471, -0.14391612190770786, 0.05 +8.897683840148977, 4.93708881492799, -0.14351052683990062, 0.05 +9.144896135658275, 4.944245910185954, -0.1431268277909581, 0.05 +9.392465392634907, 4.95138513953265, -0.142771360882481, 0.05 +9.640390802278553, 4.958508192872909, -0.14244967286686006, 0.05 +9.888671652239239, 4.965616999213736, -0.14216655365119735, 0.05 +10.137307336735386, 4.972713689922956, -0.14192604425106836, 0.05 +10.38629736484269, 4.97980056214607, -0.14173147343603532, 0.05 +10.635641367051937, 4.986880044184945, -0.14158545242853648, 0.05 +10.885339100066306, 4.993954660287366, -0.14148991498574404, 0.05 +11.135390449920077, 5.001026997075435, -0.14144610565026028, 0.05 +11.385795433406392, 5.008099669726295, -0.1414545988513538, 0.05 +11.636554197830769, 5.015175288487554, -0.14151529870318313, 0.05 +11.887667019087445, 5.022256425133513, -0.14162743906020125, 0.05 +12.139134298052504, 5.0293455793011965, -0.14178957723251173, 0.05 +12.390956555265285, 5.036445144255641, -0.14199958922667122, 0.05 +12.643134423869416, 5.043557372082597, -0.14225465786768865, 0.05 +12.89566864079183, 5.050684338448288, -0.14255125170858918, 0.05 +13.148560036093697, 5.057827906037327, -0.1428851154577515, 0.05 +13.401809520467493, 5.064989687475945, -0.14325123955144292, 0.05 +13.655418070767503, 5.072171006000212, -0.14364385968695714, 0.05 +13.909386713611188, 5.0793728568736745, -0.14405639503349832, 0.05 +14.163716506902041, 5.0865958658170785, -0.1444814581941145, 0.05 +14.418408519230772, 5.093840246574624, -0.1449108241278374, 0.05 +14.67346380715127, 5.101105758409969, -0.1453353865949758, 0.05 +14.92888339022652, 5.108391661505007, -0.14574515887002093, 0.05 +15.184668223803024, 5.115696671530086, -0.1461292574222206, 0.05 +15.440819169495407, 5.123018913847664, -0.1464758874393013, 0.05 +15.697336963452837, 5.130355879148612, -0.14677230829478916, 0.05 +15.954222182231618, 5.13770437557562, -0.14700491072941801, 0.05 +16.21147520655514, 5.145060486470401, -0.14715914164113997, 0.05 +16.469096182778674, 5.152419524470689, -0.147219630828328, 0.05 +16.727084982416223, 5.159775992750941, -0.14717014305421827, 0.05 +16.9854411597034, 5.1671235457435465, -0.14699370968328296, 0.05 +17.244163907505666, 5.174454956045371, -0.1466726722999212, 0.05 +17.503252011780493, 5.181762085496531, -0.1461888072883788, 0.05 +17.762703804940113, 5.189035863192435, -0.14552344523099947, 0.05 +18.02251711849662, 5.196266271130107, -0.14465762714483077, 0.05 +18.282689235438905, 5.20344233884569, -0.1435722876469825, 0.05 +18.543051714423072, 5.207249579683306, -0.20287545271367335, 0.05 +18.802867087745952, 5.196307466457603, -0.4693446924464162, 0.05 +19.060990702354964, 5.162472292180274, -0.8810368950790526, 0.05 +19.316271519667513, 5.105616346250976, -1.2901729674115714, 0.05 +19.567552516888156, 5.025619944412896, -1.6969138185025479, 0.05 +19.813671202147617, 4.922373705189226, -2.101466173954609, 0.05 +20.053460230887055, 4.795780574788721, -2.5040772646733345, 0.05 +20.285748105733646, 4.645757496931797, -2.9050277857857054, 0.05 +20.50935993817212, 4.472236648769485, -3.3046232611464355, 0.05 +20.72311824802921, 4.275166197141789, -3.703184143661078, 0.05 +20.926010753963098, 4.057850118677807, -4.041149000031448, 0.05 +21.117598228832463, 3.831749497387337, -4.173560506203717, 0.05 +21.297849888440552, 3.605033192161813, -4.161251295605011, 0.05 +21.466737881287298, 3.3777598569349325, -4.150116014794767, 0.05 +21.624237166622144, 3.149985706696943, -4.140105687384521, 0.05 +21.770325374408387, 2.9217641557248384, -4.131163900498711, 0.05 +21.904982651378514, 2.693145539402582, -4.123229198743816, 0.05 +22.028191499522045, 2.46417696287063, -4.116236605697043, 0.05 +22.139936610733155, 2.2349022242222145, -4.110119869566224, 0.05 +22.240204702358984, 2.0053618325165736, -4.104813061560568, 0.05 +22.328984357292853, 1.775593098677382, -4.100252230847619, 0.05 +22.40626587279882, 1.545630310119356, -4.096376509388722, 0.05 +22.4720411196764, 1.3155049375516363, -4.093129770144119, 0.05 +22.52647131169765, 1.0886038404250196, -4.030939892139147, 0.05 +22.57029538852541, 0.8764815365551148, -3.7650570433484343, 0.05 +22.604662195108858, 0.6873361316690133, -3.3550327332488705, 0.05 +22.630721876886888, 0.5211936355605671, -2.945527422386712, 0.05 +22.649625553213575, 0.3780735265337624, -2.5364110312935115, 0.05 +22.6625250504026, 0.25798994378049983, -2.1275769325719476, 0.05 +22.67057268550173, 0.160952701982661, -1.7189386827013353, 0.05 +22.674921093846955, 0.08696816690443929, -1.3104277215923834, 0.05 +22.676723096938467, 0.036040061830249784, -0.9019912848829444, 0.05 +22.677131608130527, 0.00817022384116911, -0.49359118522589635, 0.05 +22.677131608130527, 0.0, -0.1446983121296761, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueMidProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueMidProfile.csv index 232fe0bf..21a0f714 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueMidProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueMidProfile.csv @@ -1,75 +1,63 @@ -74 -3.6515143980233797E-4, 0.014606057592093519, 0.05, -0.0018257571990116896, 0.02921211518418703, 0.05, -0.005112120157232723, 0.06572725916442065, 0.05, -0.010954543194070115, 0.11684846073674782, 0.05, -0.02008332918912855, 0.18257571990116866, 0.05, -0.03322878102201292, 0.2629090366576873, 0.05, -0.05112120157232821, 0.3578484110063058, 0.05, -0.07449089371967879, 0.46739384294701175, 0.05, -0.10406816034366939, 0.591545332479812, 0.05, -0.14058330432390467, 0.7303028796047056, 0.05, -0.184401477100187, 0.8763634555256467, 0.05, -0.23552267867251228, 1.0224240314465054, 0.05, -0.29394690904086845, 1.1684846073671233, 0.05, -0.35967416820526915, 1.314545183288014, 0.05, -0.4327044561657144, 1.460605759208905, 0.05, -0.51303777292225, 1.6066663351307098, 0.05, -0.6006741184748451, 1.7527269110519028, 0.05, -0.6956134928234896, 1.8987874869728905, 0.05, -0.7978558959681841, 2.044848062893889, 0.05, -0.9074013279089099, 2.190908638814517, 0.05, -1.0242497886455415, 2.3369692147326293, 0.05, -1.1484012781782122, 2.483029790653415, 0.05, -1.2798557965069222, 2.6290903665741983, 0.05, -1.418613343631672, 2.775150942494995, 0.05, -1.5646739195524613, 2.921211518415787, 0.05, -1.7180375242692896, 3.067272094336566, 0.05, -1.8787041577821577, 3.213332670257363, 0.05, -2.046308668651263, 3.3520902173821066, 0.05, -2.2201207539970023, 3.4762417069147844, 0.05, -2.3994101109397707, 3.5857871388553697, 0.05, -2.5834464365999654, 3.6807265132038935, 0.05, -2.771499428097981, 3.7610598299603115, 0.05, -2.962838782554215, 3.826787089124677, 0.05, -3.156734197089062, 3.8779082906969453, 0.05, -3.3524553688229197, 3.9144234346771523, 0.05, -3.549271994876183, 3.936332521065262, 0.05, -3.74619484482278, 3.9384569989319473, 0.05, -3.9422346882349224, 3.920796868242844, 0.05, -4.136661222232846, 3.888530679958464, 0.05, -4.328744143936937, 3.841658434081836, 0.05, -4.517753150467593, 3.780180130613111, 0.05, -4.702957938945205, 3.704095769552236, 0.05, -4.883628206490163, 3.613405350899157, 0.05, -5.059033650222861, 3.5081088746539635, 0.05, -5.228443967263689, 3.3882063408165664, 0.05, -5.39112885473304, 3.253697749387019, 0.05, -5.546616937298711, 3.1097616513134163, 0.05, -5.694801991068302, 2.9637010753918247, 0.05, -5.835684016041815, 2.817640499470251, 0.05, -5.969263012219246, 2.6715799235486237, 0.05, -6.095538979600597, 2.525519347627032, 0.05, -6.214511918185869, 2.3794587717054227, 0.05, -6.326181827975059, 2.2333981957838134, 0.05, -6.43054870896817, 2.0873376198622218, 0.05, -6.527612561165201, 1.9412770439406124, 0.05, -6.617373384566151, 1.795216468019003, 0.05, -6.699831179171023, 1.649155892097447, 0.05, -6.774985944979814, 1.5030953161758198, 0.05, -6.842837681992526, 1.3570347402542282, 0.05, -6.903386390209157, 1.2109741643326188, 0.05, -6.956632069629708, 1.0649135884110272, 0.05, -7.002574720254179, 0.9188530124894179, 0.05, -7.04121434208257, 0.7727924365678263, 0.05, -7.072809862662285, 0.6319104115942942, 0.05, -7.097985360980534, 0.5035099663649767, 0.05, -7.117471139916924, 0.3897155787278095, 0.05, -7.131997502351062, 0.29052724868275703, 0.05, -7.142294751162557, 0.2059449762298904, 0.05, -7.149093189231017, 0.13596876136920955, 0.05, -7.15312311943605, 0.08059860410066122, 0.05, -7.155114844657263, 0.03983450442426317, 0.05, -7.155798667774268, 0.01367646234008646, 0.05, -7.155904891666667, 0.0021244778479889703, 0.05, -7.155904891666667, 0.0, 0.05, +62 +5.518719377827497E-4, 0.022074877511309987, 0.44149755022619974, 0.05 +0.0027593596889137462, 0.044149755022619926, 0.44149755022619874, 0.05 +0.007726207128958482, 0.09933694880089469, 1.1037438755654954, 0.05 +0.016556158133482456, 0.17659902009047948, 1.5452414257916958, 0.05 +0.030352956578051277, 0.2759359688913764, 1.9867389760179381, 0.05 +0.050220346338231074, 0.3973477952035959, 2.4282365262443903, 0.05 +0.07726207128958693, 0.5408344990271169, 2.869734076470419, 0.05 +0.11258187530768432, 0.7063960803619479, 3.31123162669662, 0.05 +0.15728350226808885, 0.8940325392080908, 3.7527291769228577, 0.05 +0.2124706960463661, 1.1037438755655449, 4.194226727149082, 0.05 +0.278695328580279, 1.3244926506782577, 4.414975502254257, 0.05 +0.3559573998698403, 1.5452414257912261, 4.414975502259368, 0.05 +0.4442569099150539, 1.7659902009042716, 4.414975502260909, 0.05 +0.5435938587159874, 1.9867389760186693, 4.414975502287954, 0.05 +0.6539682462725801, 2.2074877511318536, 4.414975502263685, 0.05 +0.7753800725848322, 2.4282365262450423, 4.414975502263774, 0.05 +0.9078293376527141, 2.648985301357638, 4.414975502251917, 0.05 +1.0513160414760856, 2.8697340764674273, 4.414975502195784, 0.05 +1.205840184055101, 3.0904828515803073, 4.414975502257601, 0.05 +1.3714017653897603, 3.3112316266931874, 4.414975502257601, 0.05 +1.5480007854800637, 3.5319804018060674, 4.414975502257601, 0.05 +1.735085372388229, 3.741691738163304, 4.194226727144734, 0.05 +1.931551782238691, 3.929328197009241, 3.7527291769187343, 0.05 +2.136296271155887, 4.094889778343913, 3.311231626693445, 0.05 +2.348215095264251, 4.238376482167281, 2.8697340764673562, 0.05 +2.566204510688219, 4.3597883084793665, 2.4282365262417116, 0.05 +2.789160773552227, 4.4591252572801565, 1.9867389760158005, 0.05 +3.01598013998071, 4.53638732856966, 1.545241425790067, 0.05 +3.2455588660981047, 4.591574522347894, 1.103743875564689, 0.05 +3.4767932080288455, 4.624686838614815, 0.6622463253384225, 0.05 +3.708360449604746, 4.631344831518014, 0.13315985806396924, 0.05 +3.938937874656209, 4.6115485010292545, -0.3959266097751879, 0.05 +4.167421739307274, 4.569677293021295, -0.8374241601591947, 0.05 +4.39270829968237, 4.505731207501924, -1.278921710387415, 0.05 +4.613693811905928, 4.419710244471151, -1.7204192606154578, 0.05 +4.829274532102377, 4.311614403928985, -2.161916810843323, 0.05 +5.038346716396147, 4.18144368587539, -2.6034143610718985, 0.05 +5.239806620911666, 4.029198090310384, -3.044911911300119, 0.05 +5.432550501773365, 3.854877617233985, -3.486409461527984, 0.05 +5.615474615105673, 3.658482266646157, -3.9279070117565595, 0.05 +5.787694189326541, 3.444391484417366, -4.281815644575815, 0.05 +5.948876324791702, 3.2236427093032205, -4.414975502282914, 0.05 +6.099021021501159, 3.002893934189128, -4.414975502281848, 0.05 +6.238128279454911, 2.7821451590750534, -4.414975502281493, 0.05 +6.366198098652958, 2.5613963839609255, -4.414975502282559, 0.05 +6.4832304790952975, 2.3406476088467976, -4.414975502282559, 0.05 +6.5892254207819345, 2.1198988337327407, -4.414975502281138, 0.05 +6.684182923712864, 1.899150058618595, -4.414975502282914, 0.05 +6.768102987888089, 1.6784012835045026, -4.414975502281848, 0.05 +6.84098561330761, 1.4576525083904102, -4.414975502281848, 0.05 +6.902830799971425, 1.2369037332763, -4.4149755022822035, 0.05 +6.953857520173056, 1.0205344040326203, -4.327386584873594, 0.05 +6.9948366181438075, 0.8195819594150322, -4.019048892351762, 0.05 +7.026871837759252, 0.6407043923088906, -3.577551342122831, 0.05 +7.05106692289496, 0.4839017027141601, -3.1360537918946108, 0.05 +7.068525617426501, 0.3491738906308228, -2.6945562416667457, 0.05 +7.080351665229444, 0.23652095605886103, -2.253058691439236, 0.05 +7.087648810179363, 0.1459428989983813, -1.8115611412095944, 0.05 +7.091520796151826, 0.07743971944925931, -1.37006359098244, 0.05 +7.093071367022404, 0.031011417411548337, -0.9285660407542196, 0.05 +7.093404266666668, 0.006657992885283903, -0.48706849052528867, 0.05 +7.093404266666668, 0.0, -0.13315985770567806, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueRightProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueRightProfile.csv index 87623d2b..4d4eebb6 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueRightProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueRightProfile.csv @@ -1,87 +1,78 @@ -86 -3.7017853445287896E-4, 0.014807141378115157, 0.05, -0.0020096460188789213, 0.03278934968852085, 0.05, -0.00569857286867361, 0.07377853699589378, 0.05, -0.01225709302051757, 0.1311704030368792, 0.05, -0.02250587739482403, 0.2049756874861292, 0.05, -0.037266476397632725, 0.29521198005617383, 0.05, -0.05736174798051332, 0.4019054316576119, 0.05, -0.0836163709051912, 0.5250924584935576, 0.05, -0.1168574435403362, 0.6648214527029002, 0.05, -0.15791516518339394, 0.8211544328611544, 0.05, -0.2072126588920038, 0.9859498741721973, 0.05, -0.2647652943821694, 1.1510527098033123, 0.05, -0.33059096174486263, 1.316513347253865, 0.05, -0.40471002997601585, 1.4823813646230646, 0.05, -0.4871452843710067, 1.6487050878998166, 0.05, -0.5779218326705026, 1.815530965989918, 0.05, -0.6770669723703667, 1.9829027939972823, 0.05, -0.7846100068727987, 2.1508606900486402, 0.05, -0.9005819974083968, 2.319439810711962, 0.05, -1.025015435880608, 2.4886687694442235, 0.05, -1.157943821643382, 2.6585677152554767, 0.05, -1.2994011225314746, 2.8291460177618526, 0.05, -1.4494211004373263, 3.0003995581170337, 0.05, -1.6080364814609958, 3.1723076204733873, 0.05, -1.7752779507482783, 3.3448293857456513, 0.05, -1.9511729574806893, 3.5179001346482184, 0.05, -2.1357443190402625, 3.6914272311914686, 0.05, -2.3290086259379144, 3.8652861379530354, 0.05, -2.5309744622095387, 4.039316725432488, 0.05, -2.741640474780001, 4.213320251409248, 0.05, -2.960993350617902, 4.387057516758017, 0.05, -3.1890057867729946, 4.560248723101852, 0.05, -3.425634568977293, 4.732575644085965, 0.05, -3.6703961538592513, 4.895231697639164, 0.05, -3.9223656281970047, 5.03938948675507, 0.05, -4.18060126214387, 5.164712678937305, 0.05, -4.444148264388872, 5.270940044900035, 0.05, -4.712043586187973, 5.357906435982028, 0.05, -4.983321466050652, 5.425557597253584, 0.05, -5.257019312337139, 5.473956925729736, 0.05, -5.532183478182529, 5.503283316907806, 0.05, -5.807874498892913, 5.513820414207671, 0.05, -6.082994745263126, 5.502404927404261, 0.05, -6.356470643540316, 5.469517965543802, 0.05, -6.627430402911577, 5.419195187425228, 0.05, -6.895026819471967, 5.351928331207791, 0.05, -7.158436726696407, 5.26819814448879, 0.05, -7.416859566772133, 5.168456801514512, 0.05, -7.669515318522162, 5.053115035000576, 0.05, -7.915642015035731, 4.92253393027137, 0.05, -8.15449305747151, 4.777020848715584, 0.05, -8.385334493386248, 4.616828718294728, 0.05, -8.6076131177129, 4.445572486533027, 0.05, -8.821182487023101, 4.271387386204017, 0.05, -9.02612565694172, 4.098863398372352, 0.05, -9.222521464707464, 3.927916155314908, 0.05, -9.410444199610481, 3.7584546980603397, 0.05, -9.589963455395743, 3.5903851157052333, 0.05, -9.761144114560008, 3.4236131832852776, 0.05, -9.924046426091028, 3.2580462306204176, 0.05, -10.07872614638461, 3.093594405871665, 0.05, -10.22523472051835, 2.930171482674787, 0.05, -10.363619486930157, 2.767695328236132, 0.05, -10.493923892663318, 2.606088114663243, 0.05, -10.616187710328656, 2.4452763533067547, 0.05, -10.730447250501252, 2.2851908034519086, 0.05, -10.836735564785796, 2.1257662856908732, 0.05, -10.935082637240523, 1.9669414490945303, 0.05, -11.025515561989792, 1.8086584949853712, 0.05, -11.10805870646388, 1.650862889481753, 0.05, -11.18273385945637, 1.4935030598497974, 0.05, -11.249560364339155, 1.3365300976557097, 0.05, -11.30855523779053, 1.179897469027494, 0.05, -11.359733273904489, 1.0235607222791614, 0.05, -11.403107134822747, 0.8674772183651503, 0.05, -11.43885235913879, 0.7149044863208721, 0.05, -11.467530915848567, 0.5735711341955237, 0.05, -11.489926108130568, 0.4479038456400263, 0.05, -11.506819171174218, 0.33786126087300944, 0.05, -11.51898976522346, 0.24341188098481084, 0.05, -11.527216394624912, 0.1645325880290346, 0.05, -11.532276757588477, 0.10120725927129046, 0.05, -11.53494803023496, 0.05342545292964145, 0.05, -11.536007086705492, 0.0211811294106659, 0.05, -11.536230657219681, 0.004471410283765675, 0.05, -11.536230657219681, 0.0, 0.05, +77 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002886860140275815, 0.046867637588125, 0.366995022385935, 0.05 +0.008159641112496091, 0.10545561944440551, 1.0021534842192585, 0.05 +0.01753406047316238, 0.18748838721332575, 1.4028227361340067, 0.05 +0.032183095278446296, 0.2929806961056783, 1.8031970116987073, 0.05 +0.05328093254114137, 0.4219567452539015, 2.2030868706919624, 0.05 +0.08200356426139087, 0.5744526344049898, 2.602254084067593, 0.05 +0.11952950869942215, 0.7505188887606257, 3.000409937835776, 0.05 +0.16704066235261028, 0.9502230730637626, 3.3972128512084976, 0.05 +0.2257232903260606, 1.1736525594690062, 3.7922660723495794, 0.05 +0.2961818273056074, 1.4091707395909359, 3.985266693053715, 0.05 +0.37843803357233424, 1.6451241253345372, 3.976553054872598, 0.05 +0.4725175111568969, 1.8815895516912524, 3.9663006329184647, 0.05 +0.5784497822882928, 2.1186454226279183, 3.9544774454397658, 0.05 +0.6962683629890906, 2.3563716140159543, 3.9410540025846075, 0.05 +0.8260108210415401, 2.5948491610489914, 3.926006425682438, 0.05 +0.9677188076437409, 2.8341597320440157, 3.9093216551454812, 0.05 +1.12143804669984, 3.074384781121983, 3.8910033861950755, 0.05 +1.2872182622421238, 3.3156043108456745, 3.8710799544841468, 0.05 +1.4651130194043875, 3.5578951432452732, 3.84961423716236, 0.05 +1.6551794483304423, 3.801328578521094, 3.8267158783384403, 0.05 +1.8574778136498589, 4.045967306388332, 3.802556167855471, 0.05 +2.0720708854688774, 4.291861436380368, 3.777385977023755, 0.05 +2.2984252491439903, 4.527087273502257, 3.5559172486374635, 0.05 +2.5354040647129166, 4.739576311378526, 3.1410575660375706, 0.05 +2.781859335606159, 4.929105417864853, 2.730670229778287, 0.05 +3.036629886439428, 5.095411016665383, 2.325566634178813, 0.05 +3.298539613693467, 5.23819454508078, 1.9264486875548847, 0.05 +3.5663961413943754, 5.357130554018166, 1.533856089054897, 0.05 +3.838990018395797, 5.451877540028423, 1.1481109577433735, 0.05 +4.115094585721426, 5.522091346512582, 0.7692668549868209, 0.05 +4.393466612390343, 5.567440533378336, 0.3970686151898306, 0.05 +4.672847751597191, 5.58762278413695, 0.030931710421118197, 0.05 +4.952575201530844, 5.594548998673067, -0.13866979801296253, 0.05 +5.232587423803823, 5.600244445459582, -0.11402987455136682, 0.05 +5.512818879639231, 5.6046291167081606, -0.08778731452524724, 0.05 +5.793200865408917, 5.607639715393707, -0.060276831683605536, 0.05 +6.0736624611110415, 5.6092319140424935, -0.031878407890406635, 0.05 +6.354131560292096, 5.609381983621085, -0.0030046405582950797, 0.05 +6.634535944273309, 5.608087679624251, 0.02591408164532183, 0.05 +6.914804360651752, 5.605368327568856, 0.054445694447835535, 0.05 +7.19486756549511, 5.6012640968671565, 0.08217261175394341, 0.05 +7.474659291611997, 5.595834522337745, 0.10870700940033728, 0.05 +7.753644913033341, 5.579712428426887, -0.01557033515622308, 0.05 +8.030691021271421, 5.540922164761608, -0.33508475077107747, 0.05 +8.304542551661376, 5.477030607799079, -0.702539787682035, 0.05 +8.573960038165463, 5.388349730081748, -1.0762509165067335, 0.05 +8.83772083427148, 5.275215922120338, -1.4567077934094286, 0.05 +9.094619506404554, 5.137973442661499, -1.8440683203289865, 0.05 +9.343467470351097, 4.976959278930853, -2.2381859785129876, 0.05 +9.583091980723898, 4.792490207456014, -2.638655355760555, 0.05 +9.812334610198734, 4.5848525894967045, -3.044865559204224, 0.05 +10.030049355389043, 4.354294903806159, -3.4560568709495154, 0.05 +10.235564166644702, 4.1102962251131965, -3.7186666282316416, 0.05 +10.428806969592122, 3.8648560589483902, -3.786497617524427, 0.05 +10.609837000282067, 3.620600613798882, -3.8102498153757125, 0.05 +10.778711051858725, 3.377481031533172, -3.833016945078205, 0.05 +10.935482878473831, 3.135436532302123, -3.85456153088378, 0.05 +11.08020278236668, 2.8943980778569944, -3.8747193500867994, 0.05 +11.212917344392382, 2.654291240514032, -3.8933829121459063, 0.05 +11.333669261879056, 2.4150383497334547, -3.9104884795347328, 0.05 +11.442497267799554, 2.17656011840997, -3.926004126830036, 0.05 +11.539436107363944, 1.9387767912877785, -3.939921009624321, 0.05 +11.624516553792308, 1.7016089285672682, -3.952246114343585, 0.05 +11.697765450035481, 1.4649779248634833, -3.9629961522276647, 0.05 +11.759205763383566, 1.2288062669617084, -3.9721937307747224, 0.05 +11.8093138881322, 1.0021624949726753, -3.8245764011610417, 0.05 +11.84914949210185, 0.7967120793929838, -3.4754838634727303, 0.05 +11.879898287390443, 0.6149759057718605, -3.080207775011208, 0.05 +11.90274233039797, 0.4568808601505482, -2.6834678229804454, 0.05 +11.918860918089463, 0.32237175382985545, -2.2856226718929706, 0.05 +11.929431349931235, 0.21140863683544303, -1.8869780530731788, 0.05 +11.935629562836784, 0.1239642581109648, -1.4877877706613203, 0.05 +11.938630639958786, 0.06002154244005417, -1.088256087436248, 0.05 +11.939609198795035, 0.019571176724950994, -0.6885377128716532, 0.05 +11.939739656705353, 0.002609158206368875, -0.28873958452527554, 0.05 +11.939739656705353, 0.0, -0.04441548962252892, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightBlueShootProfile.csv b/RoboRIO/src/main/resources/calciferRightBlueShootProfile.csv index 1a1322c9..3c46f067 100644 --- a/RoboRIO/src/main/resources/calciferRightBlueShootProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightBlueShootProfile.csv @@ -1,71 +1,61 @@ -70 -3.6991337507886974E-4, 0.014796535003154788, 0.05, -0.0022196195728761492, 0.03699412395594558, 0.05, -0.006381532286367266, 0.08323825426982234, 0.05, -0.013780733109952299, 0.14798401647170065, 0.05, -0.025342584249476784, 0.2312370227904897, 0.05, -0.04199284160097038, 0.3330051470298719, 0.05, -0.06465769928792851, 0.4532971537391627, 0.05, -0.09426366562458055, 0.5921193267330408, 0.05, -0.1317371302652432, 0.7494692928132527, 0.05, -0.17800342291169585, 0.9253258529290528, 0.05, -0.23352246360305734, 1.11038081382723, 0.05, -0.2982864279457631, 1.2952792868541156, 0.05, -0.3722797844986393, 1.4798671310575233, 0.05, -0.45547628029828524, 1.6639299159929188, 0.05, -0.5478355391870352, 1.8471851777749986, 0.05, -0.6492993696005318, 2.029276608269932, 0.05, -0.7597879373033504, 2.209771354056372, 0.05, -0.8791960228159912, 2.388161710252815, 0.05, -1.0073896478051032, 2.563872499782241, 0.05, -1.1442034026462964, 2.736275096823864, 0.05, -1.2894388257169376, 2.904708461412826, 0.05, -1.4428641532811037, 3.0685065512833245, 0.05, -1.60421566770579, 3.2270302884937254, 0.05, -1.7732007181443172, 3.379701008770544, 0.05, -1.9495022851911534, 3.5260313409367243, 0.05, -2.132350670553504, 3.6569677072470075, 0.05, -2.3205545029945576, 3.7640766488210686, 0.05, -2.512960189917128, 3.848113738451405, 0.05, -2.708461898651904, 3.9100341746955136, 0.05, -2.9060079466921716, 3.950920960805351, 0.05, -3.1046035771896556, 3.9719126099496784, 0.05, -3.303310601960543, 3.9741404954177475, 0.05, -3.501244717581384, 3.958682312416818, 0.05, -3.6975714224611496, 3.9265340975953142, 0.05, -3.891370831273517, 3.8759881762473474, 0.05, -4.08177131708492, 3.8080097162280584, 0.05, -4.268072494037339, 3.7260235390483802, 0.05, -4.449608165148159, 3.630713422216397, 0.05, -4.625744751467532, 3.5227317263874602, 0.05, -4.79588071269474, 3.402719224544161, 0.05, -4.959446698454104, 3.2713197151872873, 0.05, -5.115906061915744, 3.12918726923281, 0.05, -5.264755296522557, 2.976984692136249, 0.05, -5.405523929048715, 2.8153726505231593, 0.05, -5.53788681015315, 2.647257622088707, 0.05, -5.661872526544309, 2.479714327823183, 0.05, -5.7777293154876155, 2.317135778866115, 0.05, -5.8856974683478445, 2.159363057204572, 0.05, -5.986008290777821, 2.0062164485995395, 0.05, -6.078882750228376, 1.8574891890110994, 0.05, -6.164529992497679, 1.712944845386041, 0.05, -6.243145895547504, 1.572318060996504, 0.05, -6.314911801495376, 1.4353181189574404, 0.05, -6.379993530349995, 1.3016345770923805, 0.05, -6.438540736730661, 1.1709441276133175, 0.05, -6.490686628578326, 1.0429178369532945, 0.05, -6.53654802905242, 0.9172280094818822, 0.05, -6.576225733012377, 0.7935540791991376, 0.05, -6.60980508867905, 0.6715871133334519, 0.05, -6.637456794956796, 0.5530341255549304, 0.05, -6.659631016437983, 0.44348442962374485, 0.05, -6.67695643776731, 0.3465084265865556, 0.05, -6.6900479794362475, 0.26183083337874574, 0.05, -6.6995102323718685, 0.18924505871242345, 0.05, -6.705940292688861, 0.12860120633984248, 0.05, -6.70993006636578, 0.07979547353840138, 0.05, -6.712068102176946, 0.042760716223317154, 0.05, -6.7129409964016835, 0.01745788449474225, 0.05, -6.713134398306177, 0.003868038089867418, 0.05, -6.713134398306177, 0.0, 0.05, +60 +5.424561587941971E-4, 0.02169824635176788, 0.43396492703535755, 0.05 +0.003235676494508511, 0.05386440671428627, 0.22460664739822062, 0.05 +0.00929547286990161, 0.12119592750786198, 0.823194042570102, 0.05 +0.020068598431075793, 0.2154625112234837, 1.1524218955883496, 0.05 +0.03690191951923663, 0.33666642176321665, 1.4816031177330407, 0.05 +0.06114229703341459, 0.4848075502835592, 1.810783418087885, 0.05 +0.09413614910717813, 0.6598770414752709, 2.140135494450942, 0.05 +0.1372284081512695, 0.861845180881827, 2.470073000480711, 0.05 +0.19176045719746276, 1.0906409809238653, 2.801416880570655, 0.05 +0.2590664750416274, 1.346120356883293, 3.1356232920755844, 0.05 +0.33979494683814604, 1.6145694359303724, 3.310127886060068, 0.05 +0.4339028626173758, 1.8821583155845956, 3.3272610745023523, 0.05 +0.5413218599217047, 2.1483799460865773, 3.3545287562284942, 0.05 +0.6619502508532681, 2.4125678186312682, 3.395124351792318, 0.05 +0.795644670041689, 2.673888383768419, 3.4523949695448364, 0.05 +0.9422120170445702, 2.9313469400576233, 3.5295716891296935, 0.05 +1.1014025772996265, 3.183811205101126, 3.6294155176649223, 0.05 +1.2729053397018377, 3.430055248044225, 3.7538095042753294, 0.05 +1.4563465058357907, 3.668823322679059, 3.903359106746942, 0.05 +1.651291938678903, 3.8989086568622424, 4.077091465798119, 0.05 +1.8566135448745678, 4.106432123913297, 4.094538185743115, 0.05 +2.0705365247219785, 4.2784595969482115, 3.9367865995647566, 0.05 +2.2913242333699775, 4.415754172959977, 3.7637776975496173, 0.05 +2.517302109414138, 4.519557520883215, 3.5659075409220797, 0.05 +2.746875364539511, 4.591465102507465, 3.3360742789277875, 0.05 +2.9785391268726316, 4.633275246662406, 3.0702047992254933, 0.05 +3.210881297845753, 4.646843419462427, 2.7671517551229563, 0.05 +3.4425795852545127, 4.633965748175196, 2.428107020267465, 0.05 +3.6723947994358808, 4.596304283627363, 2.0557641084974954, 0.05 +3.89876174172384, 4.52733884575919, 1.5045124601387094, 0.05 +4.120207313402781, 4.428911433578808, 0.916390828657363, 0.05 +4.335731268779338, 4.310479107531158, 0.44839446372620273, 0.05 +4.5443879606983195, 4.17313383837962, -0.041427609329343085, 0.05 +4.745284116426918, 4.017923114571962, -0.5521738873938453, 0.05 +4.937578429999406, 3.845886271449766, -1.0836723822198735, 0.05 +5.120482164029664, 3.658074680605151, -1.6361581901307254, 0.05 +5.293259744562561, 3.4555516106579436, -2.209867379593371, 0.05 +5.455228254297125, 3.239370194691283, -2.8045996483358238, 0.05 +5.605754807749073, 3.0105310690389677, -3.4193119157639895, 0.05 +5.744594932273976, 2.7768024904980657, -3.8801028051433395, 0.05 +5.871998580019762, 2.5480729549157055, -4.104706419054933, 0.05 +5.988338244994405, 2.3267932994928597, -4.253646363992711, 0.05 +6.093963620609854, 2.1125075123089774, -4.393478230200545, 0.05 +6.18919870696826, 1.9047017271681232, -4.5230472412533995, 0.05 +6.274339203137478, 1.7028099233843499, -4.641310782140753, 0.05 +6.349650511460798, 1.5062261664664014, -4.74746953553618, 0.05 +6.415366537773745, 1.3143205262589557, -4.84104139152612, 0.05 +6.471689328312498, 1.1264558107750495, -4.921878183678952, 0.05 +6.518789461381933, 0.9420026613886963, -4.99013329490599, 0.05 +6.557122350402383, 0.7666577804090104, -4.863053359658789, 0.05 +6.587551331599477, 0.6085796239418756, -4.46517629984515, 0.05 +6.611033153031506, 0.4696364286405637, -3.979965551826381, 0.05 +6.628497910942368, 0.34929515821725493, -3.4840869768855898, 0.05 +6.640855942740529, 0.2471606359632299, -2.98029956434071, 0.05 +6.649003490865373, 0.16295096249687496, -2.4708706209464535, 0.05 +6.653827267429528, 0.09647553128310167, -1.957627372686881, 0.05 +6.656208034041865, 0.047615332246740395, -1.4420028290875855, 0.05 +6.657023283807152, 0.016304995305743225, -0.925070375627324, 0.05 +6.657149081643991, 0.002515956736787364, -0.40756651158333934, 0.05 +6.657149081643991, 0.0, -0.07437205338886875, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedBackupProfile.csv b/RoboRIO/src/main/resources/calciferRightRedBackupProfile.csv index 0f692b72..91efa50e 100644 --- a/RoboRIO/src/main/resources/calciferRightRedBackupProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedBackupProfile.csv @@ -1,55 +1,49 @@ -54 -3.6998202195815923E-4, 0.014799280878326368, 0.05, -0.0016598585659633087, 0.025797530880102986, 0.05, -0.00456453440812895, 0.058093516843312834, 0.05, -0.009736780007313695, 0.10344491198369492, 0.05, -0.017839832946141443, 0.16206105877655497, 0.05, -0.029553962908322025, 0.23428259924361167, 0.05, -0.04558452438091229, 0.3206112294518053, 0.05, -0.06667136828170966, 0.4217368780159476, 0.05, -0.09359946125912039, 0.5385618595482142, 0.05, -0.12721057108115189, 0.6722221964406301, 0.05, -0.16807301705612498, 0.8172489194994622, 0.05, -0.21646743551455574, 0.9678883691686153, 0.05, -0.2727166853993792, 1.1249849976964694, 0.05, -0.33718604820207904, 1.289387256053996, 0.05, -0.4102851308161053, 1.4619816522805251, 0.05, -0.492472141728961, 1.6437402182571133, 0.05, -0.5842612721242726, 1.8357826079062312, 0.05, -0.6858366380214408, 2.0315073179433645, 0.05, -0.797012208513357, 2.223511409838323, 0.05, -0.9176009722860494, 2.411775275453848, 0.05, -1.047414041904346, 2.596261392365935, 0.05, -1.1862558344826988, 2.7768358515670544, 0.05, -1.333911213786281, 2.953107586071645, 0.05, -1.4901196317568346, 3.124168359411074, 0.05, -1.6545310145635899, 3.288227656135104, 0.05, -1.8266394777861634, 3.4421692644514725, 0.05, -2.005573645763163, 3.5786833595399923, 0.05, -2.1901027948120273, 3.6905829809772848, 0.05, -2.378684170630625, 3.77162751637195, 0.05, -2.569317687572544, 3.812670338838382, 0.05, -2.759599402518522, 3.8056342989195633, 0.05, -2.9468723675604385, 3.745459300838329, 0.05, -3.128446365014604, 3.63147994908331, 0.05, -3.301823561796479, 3.467543935637492, 0.05, -3.4648638680732016, 3.2608061255344514, 0.05, -3.6158542077459583, 3.0198067934551385, 0.05, -3.7536192744114563, 2.75530133330996, 0.05, -3.877874329940669, 2.4851011105842495, 0.05, -3.988955314752371, 2.2216196962340438, 0.05, -4.087271963316606, 1.966332971284699, 0.05, -4.17324899764151, 1.719540686498076, 0.05, -4.247289766422094, 1.480815375611675, 0.05, -4.309755916464765, 1.2493230008534204, 0.05, -4.361079026063792, 1.0264621919805281, 0.05, -4.402163348463963, 0.8216864480034184, 0.05, -4.434254593872506, 0.6418249081708585, 0.05, -4.458536542344106, 0.4856389694319969, 0.05, -4.476145765944184, 0.3521844720015575, 0.05, -4.488184183890037, 0.24076835891705717, 0.05, -4.49572946901541, 0.15090570250746285, 0.05, -4.499843429203186, 0.08227920375551406, 0.05, -4.501578501017333, 0.03470143628294079, 0.05, -4.501982459636725, 0.00807917238784297, 0.05, -4.501982459636725, 0.0, 0.05, +48 +5.227250022608844E-4, 0.020909000090435375, 0.41818000180870746, 0.05 +0.002345406460912165, 0.03645362917302561, 0.5254674173012496, 0.05 +0.006451335591911113, 0.08211858261997894, 1.1776008968009792, 0.05 +0.013767472257941164, 0.14632273332060103, 1.6431767867264317, 0.05 +0.0252416135749518, 0.22948282634021272, 2.10041747617459, 0.05 +0.04185537964679664, 0.33227532143689675, 2.5441284577210452, 0.05 +0.06464003174297028, 0.4556930419234728, 2.9679823911589875, 0.05 +0.09469480172644217, 0.6010953996694376, 3.3646477135693176, 0.05 +0.13320740816002624, 0.7702521286716814, 3.725918803719417, 0.05 +0.18147657729001399, 0.9653833825997551, 4.042788778674713, 0.05 +0.2404406855302659, 1.1792821648050382, 4.085622937559972, 0.05 +0.3106506917108197, 1.4042001236110757, 3.8652476920466583, 0.05 +0.39274377157774487, 1.6418615973385027, 3.6103831837020817, 0.05 +0.487449997542536, 1.8941245192958218, 3.318346115150095, 0.05 +0.5950581139051414, 2.1521623272521073, 2.7846267278103642, 0.05 +0.7153540535348387, 2.4059187925939454, 2.033793502837975, 0.05 +0.8481273667100425, 2.655466263504076, 1.2814295903722073, 0.05 +0.9931735331474116, 2.9009233287473832, 0.5265847555005987, 0.05 +1.1502924337050313, 3.1423780111523913, -0.23015310550203338, 0.05 +1.3192736926504234, 3.379625178907842, -0.9829372101202338, 0.05 +1.4998565316137862, 3.611656779267256, -1.715706676148132, 0.05 +1.6916494090923588, 3.8358575495714518, -2.3962751385440484, 0.05 +1.893996485286556, 4.0469415238839455, -2.9711167088566137, 0.05 +2.105026501964848, 4.220600333565834, -3.4733583477648144, 0.05 +2.3220908512364358, 4.341286985431754, -3.6639875624850182, 0.05 +2.54246444525993, 4.407471880469884, -3.4094216811615263, 0.05 +2.7626881136458867, 4.404473367719135, -2.8604635188258998, 0.05 +2.978831790583079, 4.322873538743847, -2.1227074695402726, 0.05 +3.186922709672645, 4.16181838179132, -1.3679820419413158, 0.05 +3.3833823557902165, 3.9291929223514264, -0.7715724598597684, 0.05 +3.5653098057435293, 3.6385489990662516, -0.44702625251599626, 0.05 +3.7305454088039194, 3.304712061207801, -0.4197071584362355, 0.05 +3.8775596078692347, 2.9402839813063046, -0.644869150304781, 0.05 +4.006047544439516, 2.569758731405628, -0.9461892984624432, 0.05 +4.116681535994648, 2.2126798311026263, -1.2201618242302192, 0.05 +4.210153470692785, 1.8694386939627539, -1.4975487958769373, 0.05 +4.287094483589681, 1.5388202579379142, -1.7504532749080592, 0.05 +4.348789153451394, 1.2338933972342652, -1.8506325236946808, 0.05 +4.397143368340728, 0.9670842977866976, -1.781040886970986, 0.05 +4.433938830184446, 0.7359092368743548, -1.6574806168582557, 0.05 +4.460855187581871, 0.5383271479484993, -1.4930436587038225, 0.05 +4.479496530208544, 0.37282685253344716, -1.2983517262584525, 0.05 +4.491413605561774, 0.23834150706459406, -1.0823055320928565, 0.05 +4.498121773586182, 0.1341633604881728, -0.8520954061679454, 0.05 +4.501114983083297, 0.059864189942291514, -0.6133170181827531, 0.05 +4.50187605653262, 0.01522146898646303, -0.37008633317444045, 0.05 +4.501883477123806, 1.4841182371315317E-4, -0.1251196518954877, 0.05 +4.501883477123806, 0.0, -0.0012321991513610108, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedBoilerToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferRightRedBoilerToLoadingProfile.csv index 4030f2b2..9480d4ba 100644 --- a/RoboRIO/src/main/resources/calciferRightRedBoilerToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedBoilerToLoadingProfile.csv @@ -1,148 +1,152 @@ -147 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002777777777777774, 0.04444444444444436, 0.05, -0.007777777777777759, 0.0999999999999997, 0.05, -0.016666666666666625, 0.1777777777777773, 0.05, -0.03055555555555596, 0.27777777777778667, 0.05, -0.05055555555555677, 0.40000000000001623, 0.05, -0.07777777777778011, 0.5444444444444668, 0.05, -0.1133333333333371, 0.7111111111111398, 0.05, -0.1583333333333382, 0.9000000000000221, 0.05, -0.21388888888887678, 1.1111111111107712, 0.05, -0.280555555555523, 1.3333333333329238, 0.05, -0.3583333333333088, 1.5555555555557166, 0.05, -0.4472222222222322, 1.7777777777784676, 0.05, -0.5472222222222709, 2.0000000000007745, 0.05, -0.6583333333333788, 2.222222222222159, 0.05, -0.780555555555479, 2.444444444442002, 0.05, -0.9138888888886788, 2.666666666663997, 0.05, -1.0583333333329787, 2.8888888888859965, 0.05, -1.2138888888883792, 3.111111111108009, 0.05, -1.380555555554879, 3.3333333333299953, 0.05, -1.558333333332479, 3.555555555551999, 0.05, -1.7472222222211788, 3.7777777777739985, 0.05, -1.947222222220979, 3.9999999999960023, 0.05, -2.1583333333318793, 4.222222222218002, 0.05, -2.380555555553879, 4.444444444439997, 0.05, -2.6138888888876117, 4.666666666674653, 0.05, -2.8583333333331686, 4.888888888911138, 0.05, -3.113333333334329, 5.100000000023206, 0.05, -3.3777777777799773, 5.288888888912968, 0.05, -3.6505555555589964, 5.45555555558038, 0.05, -3.9305555555602707, 5.600000000025487, 0.05, -4.216666666672683, 5.722222222248261, 0.05, -4.507777777785119, 5.822222222248712, 0.05, -4.802777777786462, 5.900000000026857, 0.05, -5.109691288422086, 6.138270212712478, 0.05, -5.438037762698387, 6.566929485526008, 0.05, -5.767930011799243, 6.597844982017121, 0.05, -6.098718768426793, 6.615775132550993, 0.05, -6.430348540827205, 6.632595448008228, 0.05, -6.762748603828744, 6.648001260030781, 0.05, -7.095832702508137, 6.661681973587852, 0.05, -7.429499319929359, 6.673332348424453, 0.05, -7.763632583382258, 6.682665269057987, 0.05, -8.098103845780841, 6.689425247971635, 0.05, -8.432773929904151, 6.693401682466208, 0.05, -8.767495950872304, 6.694440419363056, 0.05, -9.102118590767137, 6.692452797896666, 0.05, -9.436489641562908, 6.687421015915387, 0.05, -9.77045959869517, 6.679399142645244, 0.05, -10.10388509530764, 6.668509932249363, 0.05, -10.436631967462759, 6.654937443102384, 0.05, -10.76857779524594, 6.638916555663634, 0.05, -11.099613807119958, 6.620720237480354, 0.05, -11.42964610266206, 6.600645910842055, 0.05, -11.758596201947679, 6.579001985712361, 0.05, -12.086400980543965, 6.556095571925737, 0.05, -12.4130120824346, 6.5322220378126765, 0.05, -12.738394922914196, 6.507656809591927, 0.05, -13.062527399361414, 6.482649528944374, 0.05, -13.385398421075326, 6.457420434278217, 0.05, -13.707006357564733, 6.432158729788131, 0.05, -14.027357484414646, 6.407022536998244, 0.05, -14.346464488888765, 6.3821400894823865, 0.05, -14.664345077942043, 6.357611781065554, 0.05, -14.98102071466497, 6.3335127344585445, 0.05, -15.29651549730643, 6.309895652829214, 0.05, -15.610855183840968, 6.2867937306907615, 0.05, -15.924066356260049, 6.264223448381625, 0.05, -16.23617571788165, 6.242187232432039, 0.05, -16.547209508598357, 6.220675814334117, 0.05, -16.85719302572516, 6.199670342536046, 0.05, -17.16615023696744, 6.179144224845614, 0.05, -17.47410347039149, 6.159064668481023, 0.05, -17.781073170209265, 6.139393996355507, 0.05, -18.087077706596318, 6.1200907277411, 0.05, -18.392133229138544, 6.101110450844483, 0.05, -18.69625355618899, 6.082406541008883, 0.05, -18.999450092309992, 6.063930722420055, 0.05, -19.301731768700098, 6.04563352780209, 0.05, -19.60310500083224, 6.027464642642825, 0.05, -19.903573660919726, 6.009373201749742, 0.05, -20.20313906209344, 5.991308023474346, 0.05, -20.50179995304164, 5.9732178189639855, 0.05, -20.799552522640887, 5.95505139198497, 0.05, -21.096390414827802, 5.936757843738294, 0.05, -21.39230475551753, 5.918286813794543, 0.05, -21.687284193604967, 5.899588761748757, 0.05, -21.98131495974953, 5.88061532289127, 0.05, -22.27438094731101, 5.86131975122962, 0.05, -22.566463821710663, 5.841657487993082, 0.05, -22.85754316476506, 5.8215868610879955, 0.05, -23.147596663232633, 5.801069969351401, 0.05, -23.43660034992819, 5.7800737339111725, 0.05, -23.72452891107277, 5.758571222891586, 0.05, -24.01135607062122, 5.736543190968942, 0.05, -24.29705506477887, 5.713979883153015, 0.05, -24.58159922327682, 5.690883169959046, 0.05, -24.864962667591396, 5.667268886291492, 0.05, -25.14712114249218, 5.643169498015624, 0.05, -25.428052986529615, 5.6186368807486895, 0.05, -25.707740249614282, 5.59374526169337, 0.05, -25.98616995289584, 5.568594065631101, 0.05, -26.263335478643175, 5.543310514946727, 0.05, -26.5392380645283, 5.5180517177024955, 0.05, -26.813888359624315, 5.493005901920358, 0.05, -27.087307981720347, 5.46839244192064, 0.05, -27.35953099580241, 5.444460281641259, 0.05, -27.630605216357836, 5.421484411108564, 0.05, -27.90059322123426, 5.399760097528482, 0.05, -28.169259623355785, 5.373328042430477, 0.05, -28.43589291466693, 5.332665826222882, 0.05, -28.699621919436144, 5.274580095384294, 0.05, -28.95959497592622, 5.19946112980154, 0.05, -29.21497256275717, 5.107551736618957, 0.05, -29.464919181359004, 4.998932372036735, 0.05, -29.708595180019557, 4.873519973211096, 0.05, -29.945149211737483, 4.731080634358525, 0.05, -30.173711932695426, 4.571254419158824, 0.05, -30.39339136941681, 4.393588734427696, 0.05, -30.60358021757753, 4.20377696321435, 0.05, -30.804138884554206, 4.011173339533496, 0.05, -30.99508929865731, 3.8190082820620366, 0.05, -31.176436529903917, 3.626944624932194, 0.05, -31.34817202186584, 3.434709839238446, 0.05, -31.510276604231322, 3.2420916473096395, 0.05, -31.662723214599854, 3.0489322073706697, 0.05, -31.805479270282834, 2.855121113659609, 0.05, -31.93850869800845, 2.660588554512376, 0.05, -32.06177361644373, 2.4652983687056365, 0.05, -32.17523571596957, 2.269241990516839, 0.05, -32.278857363865924, 2.0724329579270715, 0.05, -32.372602475677894, 1.874902236239328, 0.05, -32.456437190975485, 1.6766943059518393, 0.05, -32.53033038763152, 1.4778639331207795, 0.05, -32.5942540696458, 1.2784736402854713, 0.05, -32.64818364952626, 1.078591597609242, 0.05, -32.6924149060117, 0.8846251297087945, 0.05, -32.727750806206444, 0.7067180038948989, 0.05, -32.755185072636905, 0.5486853286091621, 0.05, -32.775715513227425, 0.4106088118104355, 0.05, -32.79034307244699, 0.2925511843912159, 0.05, -32.80007100732747, 0.19455869760954278, 0.05, -32.80590417667592, 0.11666338696891093, 0.05, -32.808848463536165, 0.05888573720503926, 0.05, -32.80991032615575, 0.021237252391720814, 0.05, -32.81009648352594, 0.0037231474036812486, 0.05, -32.81009648352594, 0.0, 0.05, +151 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.002717391304347822, 0.04347826086956514, 0.4347826086956506, 0.05 +0.007608695652173897, 0.09782608695652148, 1.0869565217391268, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.029891304347826463, 0.27173913043479087, 1.956521739130609, 0.05 +0.04945652173913161, 0.391304347826103, 2.391304347826243, 0.05 +0.07608695652174138, 0.5326086956521955, 2.8260869565218494, 0.05 +0.11086956521739495, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783155, 0.8804347826087319, 3.695652173913211, 0.05 +0.20923913043477188, 1.0869565217388066, 4.130434782601495, 0.05 +0.27445652173909973, 1.304347826086557, 4.347826086955009, 0.05 +0.350543478260842, 1.5217391304348449, 4.347826086965756, 0.05 +0.4375000000000061, 1.7391304347832826, 4.3478260869687535, 0.05 +0.5353260869565658, 1.956521739131194, 4.347826086958229, 0.05 +0.6440217391304945, 2.1739130434785747, 4.347826086947615, 0.05 +0.7635869565216794, 2.3913043478236973, 4.347826086902451, 0.05 +0.8940217391302444, 2.6086956521713, 4.347826086952056, 0.05 +1.0353260869561902, 2.826086956518914, 4.347826086952278, 0.05 +1.1874999999995164, 3.0434782608665234, 4.347826086952189, 0.05 +1.350543478260223, 3.260869565214133, 4.347826086952189, 0.05 +1.5244565217383097, 3.4782608695617334, 4.347826086952011, 0.05 +1.709239130433777, 3.6956521739093473, 4.347826086952278, 0.05 +1.904891304346625, 3.9130434782569568, 4.347826086952189, 0.05 +2.1108695652159843, 4.119565217387184, 4.130434782604553, 0.05 +2.3260869565201174, 4.304347826082662, 3.695652173909547, 0.05 +2.5494565217375595, 4.467391304348842, 3.2608695653236097, 0.05 +2.779891304347304, 4.608695652194887, 2.8260869569209035, 0.05 +3.016304347826641, 4.7282608695867445, 2.391304347837142, 0.05 +3.257608695653826, 4.826086956543696, 1.9565217391390277, 0.05 +3.5027173913071152, 4.902173913065786, 1.5217391304418015, 0.05 +3.7505434782647646, 4.956521739152988, 1.0869565217440424, 0.05 +4.000000000005031, 4.989130434805329, 0.6521739130468163, 0.05 +4.2500000000061675, 5.000000000022737, 0.217391304348169, 0.05 +4.500000000007306, 5.000000000022773, 7.105427357601002E-13, 0.05 +4.750000000008443, 5.000000000022737, -7.105427357601002E-13, 0.05 +5.000000000009582, 5.000000000022773, 7.105427357601002E-13, 0.05 +5.276969549562218, 5.539390991052737, -11.034981062003961, 0.05 +5.555614393286303, 5.572896874481703, -0.42878619312439525, 0.05 +5.835626077238715, 5.600233679048246, -0.5473053873085476, 0.05 +6.117024137326496, 5.627961201755602, -0.5551565277866821, 0.05 +6.399813044312992, 5.655778139729935, -0.5569723912871538, 0.05 +6.683978844427567, 5.683316002291488, -0.551413136126957, 0.05 +6.9694858004734055, 5.710139120916782, -0.5371270733499323, 0.05 +7.256273251727427, 5.735749025080416, -0.5128561281433264, 0.05 +7.544253008105114, 5.759595127553745, -0.4775561627110747, 0.05 +7.8333076334011125, 5.7810925059199665, -0.43053619669422005, 0.05 +8.123289964884789, 5.799646629673513, -0.37160428700175885, 0.05 +8.414024189225538, 5.814684486814993, -0.3011887821543269, 0.05 +8.705308664811087, 5.825689511710981, -0.22042147931591316, 0.05 +8.996920527222736, 5.832237248232995, -0.1311481050539598, 0.05 +9.288621898830993, 5.834027432165139, -0.035856590138649835, 0.05 +9.580167303239445, 5.830908088169064, 0.06247920788489125, 0.05 +9.871311721621291, 5.822888367636929, 0.16063023454499614, 0.05 +10.16181861771487, 5.810137921871557, 0.25537914064821976, 0.05 +10.451467267598886, 5.792972997680319, 0.34378778517655917, 0.05 +10.74005883215077, 5.771831291037703, 0.42342236720077864, 0.05 +11.027420791285063, 5.747239182685866, 0.4925063758928694, 0.05 +11.313409574984245, 5.719775673983648, 0.5499864553732969, 0.05 +11.597911435945631, 5.690037219227735, 0.5955144106570032, 0.05 +11.880841775782086, 5.658606796729082, 0.6293618804666146, 0.05 +12.1621432443019, 5.626029370396293, 0.6522924071124869, 0.05 +12.441782973496794, 5.592794583897887, 0.6654155486248925, 0.05 +12.719749301343773, 5.559326556939575, 0.6700457387694669, 0.05 +12.996048290710519, 5.5259797873349035, 0.6675785053528749, 0.05 +13.270700286518585, 5.493039916161309, 0.6593938437224622, 0.05 +13.543736682863042, 5.460727926889156, 0.6467871074786835, 0.05 +13.81519700939755, 5.429206530690192, 0.6309263511817953, 0.05 +14.085126388030282, 5.398587572654622, 0.6128293969140763, 0.05 +14.353573378091207, 5.368939801218498, 0.5933595631069899, 0.05 +14.62058819390957, 5.340296316367255, 0.5732305278828598, 0.05 +14.886221263633809, 5.312661394484762, 0.5530188945464154, 0.05 +15.150522089775652, 5.286016522836873, 0.533180719626003, 0.05 +15.413538367229968, 5.260325549086332, 0.5140688183305642, 0.05 +15.675315315415617, 5.2355389637129806, 0.4959498263545825, 0.05 +15.93589518665779, 5.211597424843459, 0.47902087616940037, 0.05 +16.19531691231783, 5.188434513200733, 0.4634227260610224, 0.05 +16.45361585876103, 5.165978928863997, 0.449253036870072, 0.05 +16.71082366545245, 5.144156133828349, 0.4365760621266723, 0.05 +16.96696814505646, 5.122889592080235, 0.42543169266114234, 0.05 +17.22207322708511, 5.102101640573051, 0.4158420367830651, 0.05 +17.476158932030714, 5.081714098912052, 0.40781732375490876, 0.05 +17.729241364503117, 5.061648649448056, 0.4013600944474227, 0.05 +17.98133271674417, 5.04182704482104, 0.396468503216294, 0.05 +18.23244127694146, 5.02217120394585, 0.3931391304411136, 0.05 +18.482571437265072, 5.002603206472241, 0.39136856135989717, 0.05 +18.731723698727812, 4.983045229254783, 0.39115456242038604, 0.05 +18.979894671616364, 4.963419457771025, 0.3924967853789596, 0.05 +19.227077071097682, 4.94364798962637, 0.39539674986398765, 0.05 +19.47325970925166, 4.92365276307954, 0.39985742573586336, 0.05 +19.718427486067895, 4.903355536324668, 0.4058822216803648, 0.05 +19.962561383353886, 4.88267794571982, 0.41347331399142817, 0.05 +20.20563846734464, 4.8615416798151125, 0.42262931713757723, 0.05 +20.447631908341734, 4.839868819941815, 0.4333423532586167, 0.05 +20.688511026834124, 4.817582369847813, 0.4455936186558951, 0.05 +20.928241379354144, 4.7946070504003835, 0.4593482027102702, 0.05 +21.166784901708922, 4.770870447095585, 0.4745490329991675, 0.05 +21.40410012798889, 4.74630452559934, 0.49110793615971815, 0.05 +21.64014251152143, 4.720847670650741, 0.5088964258568041, 0.05 +21.874864876215497, 4.694447293881355, 0.5277335362924518, 0.05 +22.108218033823224, 4.667063152154523, 0.5473726952243041, 0.05 +22.340151603832876, 4.638671400193, 0.567485261968077, 0.05 +22.57061508091491, 4.609269541640691, 0.5876447528340201, 0.05 +22.799559192308045, 4.578882227862731, 0.6073086592478028, 0.05 +23.026937586491293, 4.547567883664967, 0.6258014651676902, 0.05 +23.252708889805003, 4.5154260662741725, 0.6423018971105598, 0.05 +23.476839148899654, 4.482605181893016, 0.6558343823734702, 0.05 +23.699304652954755, 4.449310081102043, 0.665270912761482, 0.05 +23.920095096584227, 4.4158088725894595, 0.6693496738658311, 0.05 +24.139216986596235, 4.3824378002401625, 0.6667098471404742, 0.05 +24.35669714198429, 4.349603107761105, 0.6559551417541165, 0.05 +24.572586061177986, 4.317778383873894, 0.6357420250233936, 0.05 +24.78696086557763, 4.28749608799287, 0.6048965048929666, 0.05 +24.999927474906862, 4.25933218658463, 0.5625518364316129, 0.05 +25.211621647885902, 4.233883459580827, 0.5082941237974126, 0.05 +25.422208550904536, 4.211738060372636, 0.44229720728308664, 0.05 +25.63188060644297, 4.1934411107686556, 0.36542129683816427, 0.05 +25.840853526029967, 4.179458391739987, 0.27925065637402824, 0.05 +26.04902771912142, 4.163483861829, -3.283838788448179E-4, 0.05 +26.25586210609647, 4.1366877395009665, -0.5380024743908152, 0.05 +26.460693748963507, 4.096632857340768, -1.1420959419834453, 0.05 +26.662840454053086, 4.042934101791582, -1.7385152419955574, 0.05 +26.86158536744313, 3.9748982678009046, -2.321118816529353, 0.05 +27.056165588098242, 3.891604413102213, -2.8853625368544122, 0.05 +27.245765548734365, 3.79199921272246, -3.4286049255464235, 0.05 +27.429515147552184, 3.6749919763563685, -3.9500941448612004, 0.05 +27.606491977696376, 3.5395366028838557, -4.450714927825281, 0.05 +27.775726648042625, 3.384693406924969, -4.9325839640888525, 0.05 +27.93655322556685, 3.216531550484521, -5.216287349967708, 0.05 +28.08874929825119, 3.043921453686803, -5.242650102944584, 0.05 +28.232207332112907, 2.869160677234339, -5.199777263618328, 0.05 +28.366817470861587, 2.692202774973642, -5.155956309061738, 0.05 +28.492471452656943, 2.5130796359071526, -5.112754689620438, 0.05 +28.60906537670173, 2.331878480895714, -5.071282144672082, 0.05 +28.716501574242997, 2.1487239508253584, -5.03228703536184, 0.05 +28.814689797811837, 1.9637644713768339, -4.996246143930563, 0.05 +28.90354790571162, 1.7771621579956445, -4.963439771719216, 0.05 +28.983002203179804, 1.5890859493637224, -4.934001841598272, 0.05 +29.052987538562114, 1.3997067076461704, -4.907972694978642, 0.05 +29.113447242304076, 1.2091940748392402, -4.885332402601477, 0.05 +29.16433298625096, 1.017714878937715, -4.866019559164156, 0.05 +29.205960454207485, 0.8325493591304731, -4.67270792415055, 0.05 +29.23913903826959, 0.6635716812421192, -4.242088073482044, 0.05 +29.264815943026782, 0.513538095143793, -3.7514143955653156, 0.05 +29.28394605316524, 0.38260220276918233, -3.2638066648513564, 0.05 +29.297490032114414, 0.27087957898344417, -2.7785100557899476, 0.05 +29.306412721933494, 0.17845379638163178, -2.2948831775777414, 0.05 +29.31168181809099, 0.1053819231498698, -1.8123962943323295, 0.05 +29.314266806985547, 0.05169977789118507, -1.3306258142502347, 0.05 +29.315138159895625, 0.017427058201585358, -0.8492493487214583, 0.05 +29.315266777758186, 0.002572357251218391, -0.3680434949181345, 0.05 +29.315266777758186, 0.0, -0.06373156039263432, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedLeftProfile.csv b/RoboRIO/src/main/resources/calciferRightRedLeftProfile.csv index 2e5cee0b..c0c19de9 100644 --- a/RoboRIO/src/main/resources/calciferRightRedLeftProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedLeftProfile.csv @@ -1,87 +1,80 @@ -86 -3.745838238938134E-4, 0.014983352955752536, 0.05, -0.0017198123671121862, 0.026904570864367455, 0.05, -0.004746460331977385, 0.06053295929730397, 0.05, -0.010126770778407507, 0.10760620892860244, 0.05, -0.018532488507436114, 0.16811435458057208, 0.05, -0.030634542061758634, 0.24204107108645034, 0.05, -0.0471026464386699, 0.32936208753822527, 0.05, -0.06860482604674531, 0.4300435921615084, 0.05, -0.09580685861491502, 0.5440406513633941, 0.05, -0.12937164024048065, 0.6712956325113129, 0.05, -0.16962316562922625, 0.8050305077749117, 0.05, -0.21654715427589805, 0.9384797729334357, 0.05, -0.2701269753829949, 1.071596422141937, 0.05, -0.3303436803334163, 1.2043340990084284, 0.05, -0.39717605295278036, 1.3366474523872807, 0.05, -0.4706006846130457, 1.4684926332053077, 0.05, -0.5505920824349796, 1.5998279564386766, 0.05, -0.6371228195327371, 1.7306147419551505, 0.05, -0.730163737847271, 1.860818366290678, 0.05, -0.829684217590243, 1.9904095948594407, 0.05, -0.9356525266348088, 2.1193661808913147, 0.05, -1.0480362658210238, 2.247674783724299, 0.05, -1.1668029287286792, 2.375333258153109, 0.05, -1.2919205921741916, 2.5023532689102477, 0.05, -1.4233587561024659, 2.628763278565483, 0.05, -1.5610893468873217, 2.754611815697117, 0.05, -1.70508789699668, 2.8799710021871663, 0.05, -1.8553349034346158, 3.004940128758715, 0.05, -2.0118173597565026, 3.129649126437731, 0.05, -2.174530441123342, 3.254261627336794, 0.05, -2.3434793026044844, 3.378977229622848, 0.05, -2.5186809303569544, 3.5040325550493976, 0.05, -2.70016595886119, 3.629700570084715, 0.05, -2.8876566365878102, 3.749813554532401, 0.05, -3.080568597800087, 3.85823922424554, 0.05, -3.2783337328398865, 3.955302700795985, 0.05, -3.4803973257412544, 4.04127185802736, 0.05, -3.6862142122288826, 4.116337729752567, 0.05, -3.895244173097653, 4.180599217375411, 0.05, -4.1069468684455535, 4.234053906958015, 0.05, -4.320776674458818, 4.276596120265299, 0.05, -4.536177795497133, 4.308022420766309, 0.05, -4.752567960315679, 4.327803296370917, 0.05, -4.969346872450386, 4.335578242694147, 0.05, -5.1859059217579695, 4.331180986151668, 0.05, -5.401614944834772, 4.314180461536045, 0.05, -5.615821961820516, 4.284140339714882, 0.05, -5.82785380813179, 4.240636926225482, 0.05, -6.037017484734589, 4.183273532055976, 0.05, -6.242602031450821, 4.111690934324652, 0.05, -6.4438807336187445, 4.025574043358472, 0.05, -6.640113493223003, 3.9246551920851727, 0.05, -6.830561721120031, 3.8089645579405453, 0.05, -7.0148205693898635, 3.6851769653966553, 0.05, -7.192813826222904, 3.5598651366608136, 0.05, -7.36446837612974, 3.433090998136715, 0.05, -7.5297146963259305, 3.304926403923808, 0.05, -7.68848715376974, 3.175449148876191, 0.05, -7.840724151983309, 3.0447399642713733, 0.05, -7.986368165656897, 2.912880273471752, 0.05, -8.125365695331368, 2.779950593489418, 0.05, -8.257667165851489, 2.6460294104024267, 0.05, -8.383226787807125, 2.511192439112722, 0.05, -8.502002396378181, 2.3755121714211134, 0.05, -8.613955278238024, 2.2390576371968383, 0.05, -8.719049994644712, 2.10189432813376, 0.05, -8.817254206094493, 1.9640842289956062, 0.05, -8.908538503119427, 1.8256859404986971, 0.05, -8.992876245515813, 1.6867548479277106, 0.05, -9.070243411979142, 1.547343329266579, 0.05, -9.14061846172187, 1.4075009948545547, 0.05, -9.203982207665392, 1.2672749188704715, 0.05, -9.260317702668788, 1.1267099000679064, 0.05, -9.30961013785795, 0.985848703783251, 0.05, -9.351846753355296, 0.8447323099469364, 0.05, -9.387029739396263, 0.7036597208193462, 0.05, -9.415517695315172, 0.5697591183781765, 0.05, -9.438013028267168, 0.4499066590399199, 0.05, -9.455220301641162, 0.3441454674799003, 0.05, -9.467845739498848, 0.25250875715371973, 0.05, -9.476596803476244, 0.1750212795479282, 0.05, -9.482181836475588, 0.111700659986878, 0.05, -9.485309770151039, 0.06255867350903184, 0.05, -9.486689893136074, 0.027602459700699328, 0.05, -9.487031679008323, 0.00683571744498534, 0.05, -9.487031679008323, 0.0, 0.05, +79 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0025188197552753716, 0.03950682988811613, 0.5142112400995698, 0.05 +0.006963141040351839, 0.08888642570152934, 1.1863210415279413, 0.05 +0.014863483177203183, 0.15800684273702686, 1.6610698330715583, 0.05 +0.027206041422203703, 0.2468511649000104, 2.136156643681953, 0.05 +0.044975625384550376, 0.35539167924693343, 2.6117971603890555, 0.05 +0.06915498372980826, 0.4835871669051577, 3.088261427728297, 0.05 +0.1007239920270594, 0.6313801659450228, 3.565873474555381, 0.05 +0.14065870497438177, 0.7986942589464475, 4.045011747936417, 0.05 +0.1899302741548597, 0.9854313836095587, 4.526108309625944, 0.05 +0.2490115955929466, 1.1816264287617384, 4.7717212390770625, 0.05 +0.3178783743048923, 1.3773355742389142, 4.7814263233508925, 0.05 +0.39650231959991844, 1.5724789059005222, 4.792726768527329, 0.05 +0.48485121984921586, 1.7669780049859487, 4.805592105960335, 0.05 +0.5828890679922026, 1.9607569628597354, 4.819971886402925, 0.05 +0.6905762563313455, 2.153743766782857, 4.835787695113183, 0.05 +0.8078698641591318, 2.345872156555727, 4.8529237452324825, 0.05 +0.9347240672168172, 2.5370840611537084, 4.871215874522994, 0.05 +1.0710907015410753, 2.7273326864851604, 4.89043777711907, 0.05 +1.2169200207694935, 2.9165863845683626, 4.910285997553805, 0.05 +1.372161689314082, 3.104833370891773, 4.930362758317131, 0.05 +1.5367660567385424, 3.292087348489209, 4.950157867911589, 0.05 +1.7106857586344062, 3.478394037917276, 4.969030897592006, 0.05 +1.893396123071933, 3.654207288750534, 4.744062060022269, 0.05 +2.0839025315552773, 3.810128169666891, 4.272321657443552, 0.05 +2.281227069433465, 3.9464907575637547, 3.793916679955558, 0.05 +2.4844099431904456, 4.063657475139611, 3.3082827283728022, 0.05 +2.6925101111598906, 4.162003359388896, 2.815169341118775, 0.05 +2.904604974223144, 4.241897261265068, 2.31470083727924, 0.05 +3.119789025984866, 4.303681035234444, 1.80741642296109, 0.05 +3.3371714403759247, 4.3476482878211735, 1.2942785048043781, 0.05 +3.555872673688325, 4.3740246662480065, 0.7766423039904069, 0.05 +3.7750202617296993, 4.382951760827488, 0.25618366685721483, 0.05 +3.9942206939702514, 4.384008644811044, -0.02111453768110394, 0.05 +4.213556392375581, 4.386713968106608, -0.05404747445188818, 0.05 +4.433107835283245, 4.391028858153268, -0.0862042247947592, 0.05 +4.652952293466092, 4.39688916365695, -0.11708006844081353, 0.05 +4.8731626935652255, 4.404208001982668, -0.1462210766832861, 0.05 +5.093806648324925, 4.4128790951939845, -0.17323986578912098, 0.05 +5.314945681335374, 4.4227806602089785, -0.1978267387829291, 0.05 +5.536634661422332, 4.433779601739178, -0.21975567614610725, 0.05 +5.758921449227252, 4.445735756098392, -0.23888536900825486, 0.05 +5.98184674720107, 4.458505959476369, -0.25515580955246975, 0.05 +6.205444135497883, 4.471947765936271, -0.2685810156564905, 0.05 +6.429740268701976, 4.4859226640818495, -0.27923956374365844, 0.05 +6.654272917390815, 4.490652973776767, -0.5223187026999554, 0.05 +6.878075866903623, 4.476058990256152, -0.9985682890271441, 0.05 +7.100156820737332, 4.441619076674182, -1.471182805232818, 0.05 +7.319505889800907, 4.386981381271504, -1.9367742545625966, 0.05 +7.5350969743501075, 4.311821690984007, -2.395894182645275, 0.05 +7.745889495894417, 4.215850430886197, -2.8492335961485615, 0.05 +7.950830348814792, 4.098817058407498, -3.297571110621469, 0.05 +8.148855958650017, 3.9605121967045243, -3.7417283104718635, 0.05 +8.33889435835821, 3.8007679941638743, -4.182533508838944, 0.05 +8.519867215824412, 3.6194571493240484, -4.620796362936694, 0.05 +8.69118786673644, 3.426413018240552, -4.8277374737042145, 0.05 +8.85277594895606, 3.2317616443924035, -4.802420506923593, 0.05 +9.004564831244767, 3.035777645774136, -4.775805405003544, 0.05 +9.146493637527492, 2.8385761256544955, -4.751486056665701, 0.05 +9.278507035861066, 2.640267966671484, -4.729379354505623, 0.05 +9.400554992842261, 2.4409591396238963, -4.709387595045769, 0.05 +9.512592511774976, 2.2407503786543077, -4.691406832880753, 0.05 +9.614579368935024, 2.039737143200968, -4.675332322455681, 0.05 +9.706479858408551, 1.8380097894705323, -4.661062165447056, 0.05 +9.788262550845221, 1.6356538487334, -4.648500649914831, 0.05 +9.859900072229234, 1.4327504276802612, -4.637559312986572, 0.05 +9.921368904231409, 1.2293766400434938, -4.628158677714653, 0.05 +9.972649208270942, 1.0256060807906648, -4.620228758481937, 0.05 +10.01422824961307, 0.8315808268425707, -4.387140139000453, 0.05 +10.047109064345593, 0.6576162946504345, -3.925576155198678, 0.05 +10.07230663489305, 0.503951410949137, -3.4620059300415296, 0.05 +10.090838998216485, 0.3706472664687205, -2.9996567239436365, 0.05 +10.103726466167762, 0.2577493590255546, -2.538216829509523, 0.05 +10.111990971811448, 0.1652901128737185, -2.0774252081191014, 0.05 +10.116655534076134, 0.093291245293742, -1.6170676277908076, 0.05 +10.118743833641409, 0.04176599130548511, -1.1569747601255491, 0.05 +10.119279897163858, 0.010721270448995745, -0.6970201865007799, 0.05 +10.119287886805033, 1.5979282347460019E-4, -0.2371198584300373, 0.05 +10.119287886805033, 0.0, -0.0035875524916333524, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedLoadingToLoadingProfile.csv b/RoboRIO/src/main/resources/calciferRightRedLoadingToLoadingProfile.csv index a1de802d..35682cd2 100644 --- a/RoboRIO/src/main/resources/calciferRightRedLoadingToLoadingProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedLoadingToLoadingProfile.csv @@ -1,130 +1,125 @@ -129 -5.555555555555556E-4, 0.02222222222222222, 0.05, -0.002870380862296843, 0.04629650613482574, 0.05, -0.00807869996129221, 0.10416638197990735, 0.05, -0.01733780441392479, 0.18518208905265154, 0.05, -0.03180482271891366, 0.28934036609977737, 0.05, -0.05263661512308064, 0.41663584808333964, 0.05, -0.08098964051837858, 0.5670605079059587, 0.05, -0.11801979261308534, 0.7406030418941353, 0.05, -0.16488220517114247, 0.9372482511611425, 0.05, -0.2227310198921125, 1.1569762944194006, 0.05, -0.29214074281069813, 1.3881944583717132, 0.05, -0.3731064129204265, 1.6193134021945672, 0.05, -0.4656221356420943, 1.850314454433356, 0.05, -0.5696810364710433, 2.0811780165789786, 0.05, -0.6852752097767654, 2.3118834661144407, 0.05, -0.8123956641787796, 2.542409088040285, 0.05, -0.9510322650425559, 2.772732017275526, 0.05, -1.101173675185074, 3.0028282028503614, 0.05, -1.2628072952680804, 3.2326724016601296, 0.05, -1.4359192047076135, 3.462238188790659, 0.05, -1.6204941050840291, 3.6914980075283133, 0.05, -1.8165152666871287, 3.9204232320619927, 0.05, -2.023964480486758, 4.148984275992584, 0.05, -2.2428220160125028, 4.3771507105149015, 0.05, -2.473066587580486, 4.604891431359663, 0.05, -2.7146753291695913, 4.832174831782107, 0.05, -2.967623779638239, 5.05896900937295, 0.05, -3.231311605374933, 5.273756514733883, 0.05, -3.504564781887297, 5.465063530247278, 0.05, -3.7862115024360623, 5.6329344109753094, 0.05, -4.075082626088996, 5.777422473058665, 0.05, -4.370012093106152, 5.898589340343126, 0.05, -4.669837298694824, 5.996504111773434, 0.05, -4.973399417987736, 6.071242385858243, 0.05, -5.279543676159694, 6.122885163439171, 0.05, -5.587119559599033, 6.151517668786779, 0.05, -5.894980965850023, 6.157228125019807, 0.05, -6.20255560613463, 6.151492805692122, 0.05, -6.509842372954496, 6.145735336397321, 0.05, -6.816840413287636, 6.139960806662819, 0.05, -7.123549104486225, 6.134173823971773, 0.05, -7.429968030719894, 6.128378524673386, 0.05, -7.736096960162958, 6.122578588861279, 0.05, -8.041935822921896, 6.1167772551787865, 0.05, -8.347484689883077, 6.110977339223586, 0.05, -8.652743752511427, 6.105181252567001, 0.05, -8.957713303613096, 6.099391022033374, 0.05, -9.262393719178434, 6.093608311306756, 0.05, -9.56678544127854, 6.087834442002123, 0.05, -9.870888961987784, 6.082070414184899, 0.05, -10.17470480849952, 6.076316930234717, 0.05, -10.478233529194426, 6.070574413898134, 0.05, -10.781475680869613, 6.064843033503729, 0.05, -11.08443181699768, 6.059122722561325, 0.05, -11.38710247702473, 6.05341320054099, 0.05, -11.689488176702806, 6.047713993561515, 0.05, -11.99158939942292, 6.042024454402304, 0.05, -12.29340658854198, 6.036343782381186, 0.05, -12.594940140667514, 6.030671042510673, 0.05, -12.896190399892898, 6.025005184507666, 0.05, -13.197157652954944, 6.0193450612409345, 0.05, -13.497842125316003, 6.013689447221196, 0.05, -13.798243978139928, 6.0080370564784955, 0.05, -14.098363306159248, 6.0023865603864, 0.05, -14.398200136425057, 5.996736605316162, 0.05, -14.69775442793536, 5.9910858302060515, 0.05, -14.997026072140045, 5.985432884093701, 0.05, -15.29601489432456, 5.979776443690297, 0.05, -15.594720655875758, 5.974115231023936, 0.05, -15.893143057439666, 5.968448031278157, 0.05, -16.191281742984977, 5.962773710906184, 0.05, -16.48913630478852, 5.9570912360708315, 0.05, -16.786706289324535, 5.9513996907202875, 0.05, -17.083991204143143, 5.945698296372168, 0.05, -17.380990525692955, 5.939986430996271, 0.05, -17.677703708145497, 5.934263649050839, 0.05, -17.974130193207717, 5.928529701244371, 0.05, -18.270269421007793, 5.9227845560015195, 0.05, -18.56612084197233, 5.9170284192907605, 0.05, -18.86168392979508, 5.911261756454988, 0.05, -19.156958195506487, 5.905485314228149, 0.05, -19.45194320256985, 5.899700141267261, 0.05, -19.74663858310404, 5.893907610683827, 0.05, -20.041044055185694, 5.888109441633043, 0.05, -20.335159441141386, 5.882307719113847, 0.05, -20.6289846869887, 5.8765049169463195, 0.05, -20.922519882778715, 5.870703915800258, 0.05, -21.215765283919172, 5.8649080228091295, 0.05, -21.508721333374034, 5.859120989097251, 0.05, -21.80138868462188, 5.853347024956898, 0.05, -22.09376822532336, 5.847590814029591, 0.05, -22.385776696213, 5.840169417792841, 0.05, -22.676791329898045, 5.820292673700883, 0.05, -22.9657367145385, 5.778907692809132, 0.05, -23.251541832182824, 5.7161023528864785, 0.05, -23.53313989872258, 5.631961330795154, 0.05, -23.80946814277612, 5.526564881070759, 0.05, -24.07946752586741, 5.399987661825816, 0.05, -24.342082408667142, 5.252297655994609, 0.05, -24.59626016920215, 5.08355521070012, 0.05, -24.840950780727646, 4.893812230509914, 0.05, -25.075190034279863, 4.684785071044335, 0.05, -25.298550776072563, 4.467214835853973, 0.05, -25.511057216712885, 4.250128812806402, 0.05, -25.712731971922995, 4.0334951042022, 0.05, -25.903596079048896, 3.817282142518004, 0.05, -26.08366902379852, 3.601458894992505, 0.05, -26.252968775682977, 3.3859950376890846, 0.05, -26.41151183136815, 3.17086111370341, 0.05, -26.559313263696325, 2.956028646563532, 0.05, -26.696386776058816, 2.741470247249807, 0.05, -26.82274475953623, 2.527159669548305, 0.05, -26.938398352315968, 2.3130718555947465, 0.05, -27.043357499558336, 2.099182944847405, 0.05, -27.13763101245227, 1.885470257878726, 0.05, -27.2212266256094, 1.6719122631425802, 0.05, -27.294151051363336, 1.4584885150787092, 0.05, -27.356410030198994, 1.245179576713174, 0.05, -27.40809152279045, 1.0336298518291227, 0.05, -27.449815101991433, 0.8344715840196463, 0.05, -27.482648680097917, 0.6566715621296554, 0.05, -27.507659216944372, 0.5002107369290746, 0.05, -27.525912944632974, 0.36507455377202985, 0.05, -27.538475558091154, 0.2512522691636158, 0.05, -27.54641237294809, 0.158736297138755, 0.05, -27.550788454218313, 0.08752162540445171, 0.05, -27.55266871746398, 0.037605264913344066, 0.05, -27.55311800245826, 0.00898569988558091, 0.05, -27.55311800245826, 0.0, 0.05, +124 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0028493706468427182, 0.04611784771946306, 0.38199086036250035, 0.05 +0.008037577836269068, 0.10376414378852701, 1.0209870964796495, 0.05 +0.01726088378516054, 0.1844661189778294, 1.4294387657250944, 0.05 +0.0316718527994178, 0.28821938028514527, 1.837977996902651, 0.05 +0.0524226867632087, 0.41501667927581787, 2.2466622098530507, 0.05 +0.08066504040467447, 0.5648470728293153, 2.6555648327861636, 0.05 +0.11754979141016536, 0.7376950201098179, 3.0647778775125856, 0.05 +0.16422675670519515, 0.9335393059005959, 3.4744140841105997, 0.05 +0.2218443481975323, 1.152351829846743, 3.884611471455841, 0.05 +0.2909731376619202, 1.382575789287758, 4.091161099596872, 0.05 +0.3716060364847306, 1.6126579764562088, 4.09399213104348, 0.05 +0.4637344739925852, 1.8425687501570922, 4.097415229881842, 0.05 +0.567348266924623, 2.072275858640757, 4.101483092397036, 0.05 +0.6824354746868555, 2.30174415524465, 4.106253150739878, 0.05 +0.8089822456649081, 2.5309354195610503, 4.111787468028769, 0.05 +0.9469726554218745, 2.759808195139327, 4.11815069771893, 0.05 +1.0963885415118297, 2.9883177217991035, 4.125409066728523, 0.05 +1.2572093385823653, 3.216415941410712, 4.133628629896267, 0.05 +1.4294119187129726, 3.444051602612145, 4.142873655394013, 0.05 +1.6129704408006373, 3.6711704417532935, 4.1532043382528805, 0.05 +1.8078562149561015, 3.8977154831092817, 4.16467510046532, 0.05 +2.0140375872188447, 4.123627445254862, 4.177332594640859, 0.05 +2.2309079025658742, 4.337406306940593, 3.985214308219911, 0.05 +2.4572883067519173, 4.527608083720862, 3.587201126807935, 0.05 +2.692001962408193, 4.694273113125512, 3.1883838145792076, 0.05 +2.9338748601587756, 4.837457955011651, 2.7884372051825856, 0.05 +3.1817366102555393, 4.95723500193527, 2.3870439038833524, 0.05 +3.4344211892515006, 5.053691579919227, 1.9839044360074531, 0.05 +3.690767618023382, 5.126928575437623, 1.5787467788457121, 0.05 +3.9496205508763738, 5.177058657059833, 1.1713347333286706, 0.05 +4.209830758875732, 5.204204159987163, 0.7614742951419906, 0.05 +4.470255496482681, 5.208494752138972, 0.3490184622134862, 0.05 +4.73032371725553, 5.201364415456983, 0.14265862926757578, 0.05 +4.990032286206046, 5.1941713790103154, 0.14391124956008028, 0.05 +5.249378650537058, 5.186927286620254, 0.1449308685188555, 0.05 +5.5083607921462505, 5.17964283218385, 0.14573650311914932, 0.05 +5.766977180029176, 5.172327757658517, 0.14634720781058874, 0.05 +6.025226723090991, 5.164990861236284, 0.1467818756886352, 0.05 +6.283108723772294, 5.1576400136260645, 0.1470590541792305, 0.05 +6.540622832950624, 5.150282183566592, 0.14719683356666735, 0.05 +6.797769006248701, 5.142923465961531, 0.14721266063341787, 0.05 +7.054547462188099, 5.135569118787966, 0.14712331336060203, 0.05 +7.310958642219394, 5.128223600625905, 0.14694476415986202, 0.05 +7.567003172893255, 5.1208906134772025, 0.14669216849380717, 0.05 +7.822681830226438, 5.113573146663657, 0.1463798073016953, 0.05 +8.077995506220201, 5.106273519875277, 0.14602102090918834, 0.05 +8.332945177820804, 5.098993432012069, 0.14562829449554116, 0.05 +8.587531878021187, 5.091734004007643, 0.1452131383416777, 0.05 +8.841756669348431, 5.084495826544889, 0.14478619324561848, 0.05 +9.095620619550738, 5.077279004046147, 0.1443571840213309, 0.05 +9.349124779448276, 5.070083197950759, 0.14393494014196762, 0.05 +9.602270163028715, 5.062907671608768, 0.1435274688654964, 0.05 +9.855057729539675, 5.055751330219221, 0.14314190515937852, 0.05 +10.107488367648429, 5.04861276217509, 0.1427845869337041, 0.05 +10.359562881575016, 5.041490278531751, 0.14246106680552373, 0.05 +10.611281979117475, 5.034381950849194, 0.14217612681630243, 0.05 +10.862646261549306, 5.027285648636639, 0.14193381418438733, 0.05 +11.113656215297548, 5.020199074964837, 0.14173744446241088, 0.05 +11.364312205414718, 5.013119802343405, 0.14158964077749303, 0.05 +11.614614470744424, 5.0060453065941255, 0.14149232204843543, 0.05 +11.864563120810004, 4.998973001311611, 0.1414467357612459, 0.05 +12.114158134378455, 4.991900271369015, 0.14145345301665557, 0.05 +12.36339935970015, 4.984824506433912, 0.14151237522648685, 0.05 +12.612286516424193, 4.977743134480871, 0.14162273291837835, 0.05 +12.860819199205157, 4.970653655619249, 0.14178308335388579, 0.05 +13.108996883013052, 4.963553676157912, 0.14199129908742947, 0.05 +13.35681893017628, 4.956440943264531, 0.14224455654181511, 0.05 +13.604284599210235, 4.949313380679099, 0.14253932731246977, 0.05 +13.851393055455546, 4.942169124906211, 0.1428713517808866, 0.05 +14.098143383601975, 4.935006562928608, 0.14323562877160967, 0.05 +14.344534602099191, 4.927824369944325, 0.14362637048654037, 0.05 +14.590565679608822, 4.9206215501926165, 0.14403701746882547, 0.05 +14.836235553472967, 4.913397477282904, 0.1444601788679556, 0.05 +15.081543150276794, 4.906151936076527, 0.14488761515080384, 0.05 +15.326487408614131, 4.898885166746765, 0.14531023670700804, 0.05 +15.571067304054294, 4.891597908803243, 0.14571806190028624, 0.05 +15.815281876350905, 4.8842914459322255, 0.14610020050195516, 0.05 +16.059130258928914, 4.8769676515601486, 0.14644484635212507, 0.05 +16.302611710736183, 4.86962903614543, 0.14673930601812657, 0.05 +16.545725650266633, 4.86227879060901, 0.14696992854101865, 0.05 +16.788471691942977, 4.854920833526857, 0.1471222178951237, 0.05 +17.030849684542257, 4.847559851985587, 0.1471807600059627, 0.05 +17.272859751783898, 4.840201344832794, 0.14712936560474787, 0.05 +17.51450233475133, 4.83285165934863, 0.14695105985211399, 0.05 +17.75577823603801, 4.825518025733644, 0.1466282060367341, 0.05 +17.99668866530647, 4.818208585369144, 0.14614258902424737, 0.05 +18.237235285961855, 4.8109324131077384, 0.1454755539155883, 0.05 +18.477420262549376, 4.803699531750436, 0.14460815875480648, 0.05 +18.71724630841778, 4.796520917368083, 0.14352135431165536, 0.05 +18.9565651656544, 4.786377144732392, 0.07614481675211948, 0.05 +19.1947106611599, 4.762909910110005, -0.21884226451245326, 0.05 +19.430653564427708, 4.718858065356191, -0.6767034855494458, 0.05 +19.663371035276985, 4.65434941698554, -1.1371189185846475, 0.05 +19.891846221580007, 4.569503726060415, -1.599928036761522, 0.05 +20.11506774244814, 4.464430417362685, -2.064924784473412, 0.05 +20.33202907015459, 4.339226554129018, -2.531862608010087, 0.05 +20.541727828396578, 4.193975164839733, -3.0004615571384896, 0.05 +20.7431650284857, 4.028744001782411, -3.4704169632462367, 0.05 +20.935344268215665, 3.8435847945993604, -3.9414090325538353, 0.05 +21.117420635445555, 3.641527344597785, -4.346321569279716, 0.05 +21.289063101409933, 3.4328493192875977, -4.522012425809434, 0.05 +21.4503024391353, 3.2247867545073485, -4.5343261045104555, 0.05 +21.60116648682368, 3.017280953767608, -4.545466704537651, 0.05 +21.741680270293596, 2.8102756693983153, -4.555483004761118, 0.05 +21.871866144012273, 2.603717474373519, -4.564431019439308, 0.05 +21.991743944734086, 2.397556014436257, -4.572372326446565, 0.05 +22.101331153941658, 2.191744184151406, -4.579371530638996, 0.05 +22.20064306347531, 1.9862381906730948, -4.585494772968319, 0.05 +22.28969294035506, 1.780997537594994, -4.5908078341142655, 0.05 +22.368492186657697, 1.5759849260527563, -4.595374676780959, 0.05 +22.43705049168686, 1.371166100583249, -4.599255771161954, 0.05 +22.495375972290663, 1.166509612076043, -4.602507451354394, 0.05 +22.54362410316411, 0.9649626174689435, -4.538021942532335, 0.05 +22.582459591429195, 0.776709765301735, -4.242446077399515, 0.05 +22.612907497861155, 0.6089581286392204, -3.7829080977206053, 0.05 +22.635991585737152, 0.4616817575199558, -3.32284992216751, 0.05 +22.652734646034908, 0.33486120595513813, -2.862402180536091, 0.05 +22.664158764001243, 0.22848235932668287, -2.401671655068094, 0.05 +22.67128553526082, 0.142535425191545, -1.9407448359553552, 0.05 +22.675136237216417, 0.07701403911192585, -1.4796907015644345, 0.05 +22.676731960959806, 0.03191447486777863, -1.0185621014866322, 0.05 +22.67709370674013, 0.007234915606483806, -0.5573967597759291, 0.05 +22.67709370674013, 0.0, -0.1634044768262244, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedMidProfile.csv b/RoboRIO/src/main/resources/calciferRightRedMidProfile.csv index 922a0b99..947268d2 100644 --- a/RoboRIO/src/main/resources/calciferRightRedMidProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedMidProfile.csv @@ -1,75 +1,63 @@ -74 -3.657674863723679E-4, 0.014630699454894716, 0.05, -0.001828837431861839, 0.029261398909789422, 0.05, -0.005120744809213143, 0.06583814754702606, 0.05, -0.010973024591171015, 0.11704559563915744, 0.05, -0.020117211750480188, 0.18288374318618345, 0.05, -0.03328484125988563, 0.2633525901881088, 0.05, -0.051207448092132395, 0.3584521366449353, 0.05, -0.0746165672199649, 0.4681823825566501, 0.05, -0.10424373361612793, 0.5925433279232606, 0.05, -0.14082048225336619, 0.7315349727447651, 0.05, -0.18471258061805215, 0.8778419672937193, 0.05, -0.23592002871018172, 1.0241489618425914, 0.05, -0.29444282652974263, 1.1704559563912187, 0.05, -0.36028097407674875, 1.3167629509401224, 0.05, -0.43343447135119995, 1.463069945489024, 0.05, -0.5139033183531415, 1.6093769400388314, 0.05, -0.6016875150825439, 1.7556839345880482, 0.05, -0.6967870615393964, 1.9019909291370496, 0.05, -0.7992019577236992, 2.0482979236860555, 0.05, -0.9089322036354358, 2.1946049182347327, 0.05, -1.0259777992744765, 2.340911912780812, 0.05, -1.1503387446409574, 2.487218907329618, 0.05, -1.282015039734878, 2.6335259018784107, 0.05, -1.4210066845562388, 2.7798328964272168, 0.05, -1.5673136791050397, 2.9261398909760183, 0.05, -1.7209360233812807, 3.07244688552482, 0.05, -1.8818737173849616, 3.218753880073617, 0.05, -2.0497609936297105, 3.3577455248949795, 0.05, -2.2238663171427837, 3.4821064702614635, 0.05, -2.4034581529514365, 3.5918367161730558, 0.05, -2.587804966082926, 3.6869362626297875, 0.05, -2.7761752215645066, 3.767405109631614, 0.05, -2.967837384423436, 3.833243257178589, 0.05, -3.162059919686969, 3.884450705270659, 0.05, -3.3581112923823624, 3.921027453907868, 0.05, -3.5552599675368715, 3.9429735030901814, 0.05, -3.7525312695408855, 3.94542604008028, 0.05, -3.9489505227831505, 3.928385064845301, 0.05, -4.143786192290735, 3.896713390151696, 0.05, -4.336306743090891, 3.8504110160031146, 0.05, -4.525780640210868, 3.7894779423995395, 0.05, -4.7114763486779205, 3.7139141693410593, 0.05, -4.8926623335193, 3.6237196968275853, 0.05, -5.068607059762257, 3.5188945248591352, 0.05, -5.238578992434045, 3.3994386534357623, 0.05, -5.4018465965619145, 3.2653520825573956, 0.05, -5.557921477810899, 3.1214976249796855, 0.05, -5.706681009332403, 2.9751906304300846, 0.05, -5.848125191126426, 2.828883635880466, 0.05, -5.982254023192968, 2.6825766413308294, 0.05, -6.10906750553203, 2.5362696467812462, 0.05, -6.228565638143611, 2.3899626522316275, 0.05, -6.340748421027711, 2.243655657681991, 0.05, -6.4456158541843305, 2.09734866313239, 0.05, -6.543167937613471, 1.951041668582807, 0.05, -6.633404671315129, 1.8047346740331704, 0.05, -6.716326055289306, 1.658427679483534, 0.05, -6.791932089536004, 1.5121206849339508, 0.05, -6.86022277405522, 1.365813690384332, 0.05, -6.921198108846957, 1.2195066958347311, 0.05, -6.974858093911212, 1.0731997012851124, 0.05, -7.021202729247986, 0.926892706735476, 0.05, -7.06023201485728, 0.780585712185875, 0.05, -7.092189091376872, 0.6391415303918357, 0.05, -7.117682866930918, 0.5098755110809172, 0.05, -7.137444876492164, 0.3952401912249215, 0.05, -7.152206655033357, 0.2952355708238663, 0.05, -7.162699737527248, 0.20986164987782274, 0.05, -7.169655658946584, 0.13911842838671973, 0.05, -7.173805954264112, 0.08300590635055727, 0.05, -7.1758821584525805, 0.04152408376937089, 0.05, -7.176615806484739, 0.014672960643178357, 0.05, -7.176738433333331, 0.00245253697183756, 0.05, -7.176738433333331, 0.0, 0.05, +62 +5.49931793657908E-4, 0.02199727174631632, 0.4399454349263264, 0.05 +0.0027496589682895374, 0.043994543492632585, 0.43994543492632526, 0.05 +0.007699045111210697, 0.09898772285842318, 1.0998635873158118, 0.05 +0.016497953809737204, 0.1759781739705301, 1.5398090222421381, 0.05 +0.030246248651184988, 0.27496589682895567, 1.9797544571685115, 0.05 +0.05004379322287049, 0.39595089143370993, 2.419699892095085, 0.05 +0.07699045111210907, 0.5389331577847717, 2.859645327021235, 0.05 +0.11218608590621662, 0.7039126958821509, 3.299590761947584, 0.05 +0.156730561192509, 0.8908895057258472, 3.739536196873927, 0.05 +0.2117237405583021, 1.0998635873158618, 4.17948163180029, 0.05 +0.27771555579723384, 1.3198363047786348, 4.3994543492554605, 0.05 +0.3547060069093173, 1.5398090222416694, 4.399454349260692, 0.05 +0.4426950938945572, 1.7597817397047977, 4.399454349262566, 0.05 +0.5416828167530191, 1.9797544571692383, 4.399454349288812, 0.05 +0.6516691754846433, 2.1997271746324842, 4.39945434926492, 0.05 +0.7726541700894299, 2.4196998920957324, 4.399454349264964, 0.05 +0.9046378005673469, 2.639672609558339, 4.39945434925213, 0.05 +1.0476200669182596, 2.8596453270182565, 4.399454349198351, 0.05 +1.20160096914232, 3.079618044481207, 4.399454349259013, 0.05 +1.3665805072395272, 3.2995907619441445, 4.399454349258747, 0.05 +1.5425586812098822, 3.5195634794070996, 4.399454349259102, 0.05 +1.7289855592597265, 3.7285375609968874, 4.179481631795756, 0.05 +1.924761277801746, 3.9155143708403894, 3.7395361968700414, 0.05 +2.1287859732486254, 4.0804939089375925, 3.29959076194406, 0.05 +2.339959782013051, 4.223476175288514, 2.859645327018434, 0.05 +2.5571828405077075, 4.344461169893128, 2.419699892092275, 0.05 +2.77935528514528, 4.4434488927514515, 1.9797544571664716, 0.05 +3.0053772523384548, 4.520439343863494, 1.5398090222408456, 0.05 +3.2341488784999153, 4.57543252322921, 1.0998635873143314, 0.05 +3.4645703000423484, 4.608428430848663, 0.6599181523890607, 0.05 +3.6952836182124607, 4.614266363402244, 0.11675865107161343, 0.05 +3.9249309342554115, 4.592946320859017, -0.42640085086453894, 0.05 +4.152412384583538, 4.5496290065625455, -0.8663462859294313, 0.05 +4.376628105609524, 4.484314420519713, -1.306291720856656, 0.05 +4.596478233746043, 4.3970025627303855, -1.7462371557865453, 0.05 +4.81086290540578, 4.2876934331947325, -2.1861825907130594, 0.05 +5.0186822570014105, 4.156387031912612, -2.6261280256424158, 0.05 +5.218836424945615, 4.003083358884094, -3.066073460570351, 0.05 +5.410225545651072, 3.8277824141091443, -3.506018895498997, 0.05 +5.5917497555304605, 3.630484197587762, -3.9459643304276426, 0.05 +5.76256722616338, 3.416349412658395, -4.2826956985873466, 0.05 +5.922386060923093, 3.1963766951942496, -4.399454349282905, 0.05 +6.071206259809596, 2.976403977730069, -4.399454349283616, 0.05 +6.209027822822892, 2.7564312602659236, -4.399454349282905, 0.05 +6.335850749962979, 2.536458542801725, -4.399454349283971, 0.05 +6.4516750412298585, 2.3164858253375975, -4.39945434928255, 0.05 +6.55650069662353, 2.0965131078734345, -4.3994543492832605, 0.05 +6.650327716143992, 1.876540390409236, -4.399454349283971, 0.05 +6.7331560997912465, 1.6565676729450907, -4.399454349282905, 0.05 +6.804985847565294, 1.4365949554809454, -4.399454349282905, 0.05 +6.86581695946613, 1.216622238016729, -4.399454349284326, 0.05 +6.915907470660681, 1.0018102238910132, -4.296240282514319, 0.05 +6.956065348109526, 0.8031575489768983, -3.9730534982822974, 0.05 +6.987390455399983, 0.6265021458091447, -3.5331080633550727, 0.05 +7.010982656119375, 0.47184401438784107, -3.0931626284260716, 0.05 +7.0279418138550245, 0.33918315471298754, -2.6532171934970705, 0.05 +7.039367792194249, 0.22851956678449525, -2.213271758569846, 0.05 +7.046360454724372, 0.13985325060245302, -1.7733263236408447, 0.05 +7.050019665032712, 0.07318420616680754, -1.3333808887129095, 0.05 +7.051445286706593, 0.02851243347761212, -0.8934354537839084, 0.05 +7.051737183333333, 0.005837932534795698, -0.45349001885632845, 0.05 +7.051737183333333, 0.0, -0.11675865069591396, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedRightProfile.csv b/RoboRIO/src/main/resources/calciferRightRedRightProfile.csv index d7b34c90..9203e9a1 100644 --- a/RoboRIO/src/main/resources/calciferRightRedRightProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedRightProfile.csv @@ -1,90 +1,79 @@ -89 -3.676470588235294E-4, 0.014705882352941176, 0.05, -0.0019667207953946893, 0.0319814747314232, 0.05, -0.00556472165274023, 0.07196001714691082, 0.05, -0.011961458081997778, 0.12793472858515093, 0.05, -0.021957103444527847, 0.19991290725060137, 0.05, -0.03635242861447381, 0.2879065033989192, 0.05, -0.05594909397462698, 0.3919333072030634, 0.05, -0.0815499996471897, 0.5120181134512545, 0.05, -0.11395969646573761, 0.6481939363709583, 0.05, -0.15398485654031796, 0.8005032014916069, 0.05, -0.20203430462287497, 0.9609889616511403, 0.05, -0.2581185731875276, 1.121685371293053, 0.05, -0.3222499675541347, 1.2826278873321417, 0.05, -0.39444256630317753, 1.4438519749808558, 0.05, -0.4747122160195215, 1.6053929943268799, 0.05, -0.5630765166631702, 1.7672860128729728, 0.05, -0.6595547959398839, 1.9295655855342746, 0.05, -0.7641680666324254, 2.0922654138508308, 0.05, -0.8769389637785089, 2.255417942921669, 0.05, -0.9978916539986902, 2.419053804403626, 0.05, -1.1270517123636137, 2.5832011672984683, 0.05, -1.2644459570502316, 2.7478848937323574, 0.05, -1.410102235039092, 2.91312555977721, 0.05, -1.5640491462109503, 3.078938223437167, 0.05, -1.7263156982054721, 3.245331039890438, 0.05, -1.8969308784814043, 3.412303605518641, 0.05, -2.0759231325026595, 3.5798450804251005, 0.05, -2.263319737868635, 3.7479321073195164, 0.05, -2.459146063134334, 3.916526505313972, 0.05, -2.663424706255919, 4.085572862431709, 0.05, -2.8761745080033876, 4.25499603494937, 0.05, -3.0974094458952406, 4.424698757837062, 0.05, -3.3271374195893166, 4.594559473881523, 0.05, -3.565358951936992, 4.764430646953507, 0.05, -3.811654476519808, 4.925910491656316, 0.05, -4.065181204963364, 5.070534568871123, 0.05, -4.325083223920688, 5.198040379146462, 0.05, -4.590492258592512, 5.3081806934364835, 0.05, -4.860529074740904, 5.400736322967832, 0.05, -5.134305494387554, 5.475528392933009, 0.05, -5.410926948497496, 5.532429082198833, 0.05, -5.689495438759478, 5.571369805239646, 0.05, -5.969112740054404, 5.592346025898542, 0.05, -6.248883650254699, 5.5954182040058935, 0.05, -6.528068541771271, 5.5836978303314355, 0.05, -6.805935792299004, 5.557345010554662, 0.05, -7.0816148239083985, 5.513580632187883, 0.05, -7.354247701926256, 5.452657560357143, 0.05, -7.6229903202686025, 5.374852366846926, 0.05, -7.8870129694820434, 5.280452984268827, 0.05, -8.145500328401177, 5.169747178382667, 0.05, -8.397650953263577, 5.043012497248004, 0.05, -8.642676358540085, 4.900508105530148, 0.05, -8.879799790624864, 4.742468641695568, 0.05, -9.108510964430666, 4.5742234761160505, 0.05, -9.328708220482659, 4.4039451210398495, 0.05, -9.540438074442962, 4.234597079206065, 0.05, -9.743747154128375, 4.066181593708247, 0.05, -9.938681506709198, 3.898687051616476, 0.05, -10.12528606451509, 3.7320911561178343, 0.05, -10.303604243895096, 3.5663635876001343, 0.05, -10.473677654115738, 3.40146820441285, 0.05, -10.635545895354001, 3.2373648247652542, 0.05, -10.78924642913702, 3.074010675660382, 0.05, -10.934814503970426, 2.911361496668136, 0.05, -11.072283125167536, 2.7493724239421815, 0.05, -11.201683057225425, 2.587998641157788, 0.05, -11.323042850366935, 2.427195862830199, 0.05, -11.436388884608432, 2.2669206848299357, 0.05, -11.541745424842826, 2.1071308046878747, 0.05, -11.639134683562265, 1.9477851743887837, 0.05, -11.728576886990217, 1.788844068559048, 0.05, -11.810090342095808, 1.6302691021118432, 0.05, -11.883691502635292, 1.4720232107896964, 0.05, -11.949395032412992, 1.3140705955539855, 0.05, -12.007213864172199, 1.1563766351841291, 0.05, -12.057159254369521, 0.9989078039464538, 0.05, -12.09924083165344, 0.8416315456783708, 0.05, -12.133716034128508, 0.6895040495013695, 0.05, -12.161232542048863, 0.5503301584071166, 0.05, -12.182578836178969, 0.42692588260213504, 0.05, -12.19854184893087, 0.3192602550380008, 0.05, -12.209907339126968, 0.22730980392195205, 0.05, -12.217460211140653, 0.15105744027369278, 0.05, -12.221984780831315, 0.09049139381324756, 0.05, -12.224264990081364, 0.045604185000974774, 0.05, -12.225084571307804, 0.016391624528793523, 0.05, -12.22522716272185, 0.0028518282809276174, 0.05, -12.22522716272185, 0.0, 0.05, +78 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0029269035751671563, 0.047668506285951824, 0.35097771303500613, 0.05 +0.00828982773405713, 0.10725848317779947, 0.9821133784548175, 0.05 +0.017824658552323965, 0.19069661636533664, 1.3747156137997143, 0.05 +0.03272473572403382, 0.29800154343419705, 1.7669442995799494, 0.05 +0.054184927082725064, 0.42920382717382494, 2.1585618322786653, 0.05 +0.0834023705613429, 0.5843488695723569, 2.5492699298463104, 0.05 +0.12157736709358202, 0.7634999306447822, 2.9387115770173753, 0.05 +0.16991441913386618, 0.9667410408056828, 3.3264702254694245, 0.05 +0.2296234131025263, 1.1941798793732024, 3.7120717712240103, 0.05 +0.3013232158925155, 1.4339960557997837, 3.899295080201919, 0.05 +0.38504048579411587, 1.6743453980320082, 3.88861739836718, 0.05 +0.4808062037396704, 1.9153143589110904, 3.876207178846003, 0.05 +0.5886555516645161, 2.156986958496913, 3.8621125874969797, 0.05 +0.7086277223275743, 2.3994434132611633, 3.846409696669628, 0.05 +0.8407656332590439, 2.6427582186293908, 3.8292117481625754, 0.05 +0.9851155173841075, 2.8869976825012733, 3.8106823635456255, 0.05 +1.1417263511724447, 3.132216675766746, 3.7910492443115107, 0.05 +1.3106490802051705, 3.3784545806545143, 3.7706219069751423, 0.05 +1.4919355920890236, 3.625730237677063, 3.74981013543656, 0.05 +1.685637387353164, 3.8740359052828093, 3.729145470577686, 0.05 +1.8918038941430333, 4.123330135797385, 3.7093017679927964, 0.05 +2.1104803788459696, 4.373529694058727, 3.6911147570355585, 0.05 +2.3410964434888943, 4.612321292858492, 3.484431672578996, 0.05 +2.582458104306666, 4.827233216355435, 3.0924385640735785, 0.05 +2.83335146997556, 5.017867313377884, 2.708428613134357, 0.05 +3.0925414432927396, 5.1837994663435865, 2.3329246602227904, 0.05 +3.358771483174088, 5.324600797626962, 1.9660234919417974, 0.05 +3.630764601474054, 5.43986236599933, 1.6073265899384204, 0.05 +3.9072256802703333, 5.529221575925581, 1.2559051978856672, 0.05 +4.1868450764776295, 5.592387924145932, 0.910313898821542, 0.05 +4.468303341221207, 5.629165294871556, 0.568659223665513, 0.05 +4.750276748850043, 5.639468152576708, 0.22872250298359376, 0.05 +5.032055464432473, 5.635574311648603, 0.07796507400666286, 0.05 +5.31354580246387, 5.629806760627953, 0.11548072252448804, 0.05 +5.5946586415995725, 5.622256782714042, 0.151167574279647, 0.05 +5.875310829693357, 5.613043761875703, 0.18446268796385112, 0.05 +6.155426338694083, 5.602310180014503, 0.2149034779349357, 0.05 +6.4349371372474025, 5.590215971066388, 0.24214049435780538, 0.05 +6.713783768712503, 5.576932629302008, 0.2659423510931447, 0.05 +6.991915640718291, 5.562637440115779, 0.28619327049971943, 0.05 +7.269291047867098, 5.547508142976124, 0.3028843988908392, 0.05 +7.545876960823099, 5.531718259120019, 0.31610047743587444, 0.05 +7.821648622335939, 5.515433230256794, 0.3260035784185078, 0.05 +8.096416693860837, 5.495361430497972, 0.27621051279991704, 0.05 +8.369406080442406, 5.459787731631396, 0.025959012799159353, 0.05 +8.63943555572274, 5.400589505606666, -0.3710829355293477, 0.05 +8.905343691036819, 5.318162706281584, -0.7760587331448221, 0.05 +9.165987226960967, 5.212870718482961, -1.1883156223567504, 0.05 +9.420239077577031, 5.085037012321308, -1.6070531817891798, 0.05 +9.666986118554396, 4.934940819547302, -2.0313845458759516, 0.05 +9.905126887910313, 4.762815387118331, -2.460387781008606, 0.05 +10.133569298807318, 4.568848217940093, -2.893146032188847, 0.05 +10.351228434927275, 4.353182722399138, -3.3287756584467854, 0.05 +10.557192171281581, 4.119274727086137, -3.7079925058245777, 0.05 +10.751129919258469, 3.8787549595377584, -3.885047303469129, 0.05 +10.933118862056057, 3.6397788559517594, -3.9159603763231754, 0.05 +11.103229287421797, 3.4022085073148083, -3.9441081684084, 0.05 +11.261524928404254, 3.1659128196491353, -3.969628388252664, 0.05 +11.408063329687241, 2.9307680256597357, -3.992668364015204, 0.05 +11.542896217522166, 2.696657756698485, -4.013377106345342, 0.05 +11.666069860210706, 2.4634728537707926, -4.031899222982656, 0.05 +11.777625408283875, 2.2311109614633544, -4.048371714872467, 0.05 +11.8775992102873, 1.9994760400685008, -4.062920998281889, 0.05 +11.96602309892738, 1.768477772801598, -4.075662188177542, 0.05 +12.042924647204346, 1.5380309655393432, -4.086697918000475, 0.05 +12.108327393207828, 1.3080549200696272, -4.096118342592536, 0.05 +12.162416228780407, 1.0817767114515653, -4.044546029570513, 0.05 +12.205944068619486, 0.8705567967815812, -3.785399450776732, 0.05 +12.240066256364756, 0.6824437549054058, -3.377974004046602, 0.05 +12.265934270193144, 0.5173602765677655, -2.969001432345718, 0.05 +12.284696643000816, 0.3752474561534228, -2.558850258903871, 0.05 +12.297499740623595, 0.2560619524555835, -2.147831692916183, 0.05 +12.305488408696931, 0.15977336146672824, -1.7362049772638855, 0.05 +12.309806498388182, 0.08636179382503076, -1.3241802985540134, 0.05 +12.311597275845134, 0.03581554913902305, -0.9119215315504878, 0.05 +12.312003719327572, 0.008128869648755244, -0.49954762449480866, 0.05 +12.312003719327572, 0.0, -0.14667194496173624, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightRedShootProfile.csv b/RoboRIO/src/main/resources/calciferRightRedShootProfile.csv index b4011672..5913b62b 100644 --- a/RoboRIO/src/main/resources/calciferRightRedShootProfile.csv +++ b/RoboRIO/src/main/resources/calciferRightRedShootProfile.csv @@ -1,71 +1,61 @@ -70 -3.741170593125583E-4, 0.014964682372502331, 0.05, -0.001559391832169425, 0.02370549545713733, 0.05, -0.004226323207576404, 0.05333862750813958, 0.05, -0.008967754469693463, 0.09482862524234119, 0.05, -0.016376822843475684, 0.1481813674756444, 0.05, -0.027047189231560402, 0.2134073277616943, 0.05, -0.041573389747598416, 0.2905240103207603, 0.05, -0.060551371243092345, 0.37955962990987857, 0.05, -0.08457930004063757, 0.4805585759509044, 0.05, -0.11425876470222124, 0.5935892932316732, 0.05, -0.14989939732587462, 0.7128126524730677, 0.05, -0.19151972109449933, 0.8324064753724942, 0.05, -0.2391452549026425, 0.9525106761628633, 0.05, -0.2928102469030147, 1.073299840007444, 0.05, -0.35255957051332254, 1.1949864722061558, 0.05, -0.4184507187248407, 1.317822964230363, 0.05, -0.4905558099631169, 1.442101824765523, 0.05, -0.5689634968381336, 1.5681537375003352, 0.05, -0.6537806483564662, 1.6963430303666511, 0.05, -0.7451336653028611, 1.8270603389278979, 0.05, -0.8431692872312053, 1.9607124385668857, 0.05, -0.9480547673589277, 2.0977096025544464, 0.05, -1.0599773274983335, 2.2384512027881165, 0.05, -1.1791428618106217, 2.3833106862457645, 0.05, -1.3057739299573865, 2.532621362935298, 0.05, -1.4397856268862306, 2.680233938576879, 0.05, -1.5807643914413345, 2.8195752911020775, 0.05, -1.728272453871951, 2.95016124861233, 0.05, -1.8818414511896129, 3.071379946353238, 0.05, -2.0409677469683034, 3.1825259155738084, 0.05, -2.20510957096872, 3.2828364800083363, 0.05, -2.3736858668532146, 3.3715259176898873, 0.05, -2.546076564300028, 3.447813948936265, 0.05, -2.7216238929122856, 3.510946572245151, 0.05, -2.899613249153358, 3.5597871248214465, 0.05, -3.079295497854859, 3.5936449740300125, 0.05, -3.2599107288899676, 3.612304620702172, 0.05, -3.4406695921307686, 3.615177264816019, 0.05, -3.620754851940753, 3.601705196199684, 0.05, -3.7993225672800155, 3.5713543067852487, 0.05, -3.975502968028032, 3.523608014960332, 0.05, -4.148401163045274, 3.457963900344839, 0.05, -4.317097860626962, 3.373933951633763, 0.05, -4.480650305001332, 3.271048887487414, 0.05, -4.63811697165979, 3.1493333331691473, 0.05, -4.788936669239262, 3.0163939515894436, 0.05, -4.932922656606291, 2.8797197473405856, 0.05, -5.069895904587324, 2.739464959620658, 0.05, -5.199685292153654, 2.5957877513265912, 0.05, -5.3221279803116355, 2.448853763159635, 0.05, -5.437069894481641, 2.2988382834001118, 0.05, -5.544366249634185, 2.1459271030508775, 0.05, -5.643882060324742, 1.9903162138111512, 0.05, -5.73549258916742, 1.8322105768535717, 0.05, -5.819083700741634, 1.671822231484268, 0.05, -5.894552102076739, 1.509368026702115, 0.05, -5.961805464443177, 1.345067247328763, 0.05, -6.0207624331230045, 1.179139373596552, 0.05, -6.071352541412124, 1.0118021657823884, 0.05, -6.113541189903294, 0.8437729698233846, 0.05, -6.147732167987178, 0.6838195616776894, 0.05, -6.174744614175837, 0.5402489237731772, 0.05, -6.195409618312877, 0.4133000827407952, 0.05, -6.210567470019744, 0.3031570341373336, 0.05, -6.221065302912832, 0.20995665786175338, 0.05, -6.22775511432722, 0.1337962282877506, 0.05, -6.231492142014684, 0.07474055374928713, 0.05, -6.233133582909522, 0.03282881789676049, 0.05, -6.233537643493248, 0.008081211674527954, 0.05, -6.233537643493248, 0.0, 0.05, +60 +5.571761821131456E-4, 0.022287047284525824, 0.4457409456905165, 0.05 +0.002339172429744792, 0.03563992495263292, 0.6244243285693061, 0.05 +0.006348821401153143, 0.08019297942816703, 1.337643512521225, 0.05 +0.013477636790894186, 0.14257630779482086, 1.8725193939153175, 0.05 +0.024617876637049944, 0.2228047969231151, 2.4070964415086786, 0.05 +0.04066314455146898, 0.3209053582883806, 2.941133084377572, 0.05 +0.06250933274002804, 0.43692376377118103, 3.474250281885266, 0.05 +0.09105609244618089, 0.570935194123057, 4.005857399721566, 0.05 +0.12720909510517442, 0.7230600531798709, 4.535046835162415, 0.05 +0.17188343419066232, 0.8934867817097577, 5.060453699109182, 0.05 +0.22556095769046014, 1.0735504699959564, 5.3134081245059495, 0.05 +0.2882928393010401, 1.2546376322115986, 5.2928889323554085, 0.05 +0.3601500426483054, 1.4371440669453057, 5.264450000734393, 0.05 +0.441228000397782, 1.6215591549895316, 5.226222612293938, 0.05 +0.531651404734171, 1.8084680867277818, 5.176294540281026, 0.05 +0.6315787498308411, 1.9985469019333997, 5.1128536924183, 0.05 +0.7412061888090189, 2.1925487795635563, 5.034362754966608, 0.05 +0.8607702266793, 2.391280757405622, 4.939750382210457, 0.05 +0.9905487927298878, 2.5955713210117564, 4.828592977707551, 0.05 +1.1308603447594512, 2.806231040591267, 4.701253014125308, 0.05 +1.2815858253838743, 3.0145096124884643, 4.303243100192153, 0.05 +1.4421355659808248, 3.210994811939011, 3.6477963355920373, 0.05 +1.6118940542478237, 3.395169765339978, 3.0026944145903833, 0.05 +1.7902047036657331, 3.566212988358189, 2.3740100162402378, 0.05 +1.9763576637004014, 3.7230592006933643, 1.7666023314850143, 0.05 +2.16958153803737, 3.8644774867393754, 1.1837724532838223, 0.05 +2.3690391628551253, 3.989152496355103, 0.6272035917753627, 0.05 +2.5738269742975466, 4.095756228848429, 0.09714922213134969, 0.05 +2.7829770828280753, 4.183002170610571, -0.40721510019523066, 0.05 +2.9953597939913714, 4.247654223265918, -0.9312630581620063, 0.05 +3.2097839762680214, 4.288483645532999, -1.4307587957591572, 0.05 +3.4251053334551598, 4.30642714374277, -1.8646246240627207, 0.05 +3.6401315382373904, 4.300524095644609, -2.279276849593135, 0.05 +3.8536250180675284, 4.269869596602757, -2.675820808023026, 0.05 +4.064304890623036, 4.213597451110149, -3.0550234558353395, 0.05 +4.270848315699801, 4.130868501535307, -3.417420461241951, 0.05 +4.471891684918652, 4.020867384377009, -3.763485050721398, 0.05 +4.666032156342348, 3.882809428473931, -4.093831067881721, 0.05 +4.851830051059217, 3.7159578943373774, -4.4094198579280075, 0.05 +5.0279255872826685, 3.5219107244690253, -4.672576588122119, 0.05 +5.193536907471804, 3.3122264037827254, -4.721159398653381, 0.05 +5.348374284326214, 3.096747537088199, -4.605233782752416, 0.05 +5.492165647882796, 2.8758272711316426, -4.496376207982387, 0.05 +5.624657695661503, 2.6498409555741333, -4.395032728002564, 0.05 +5.745617062774454, 2.419187342259036, -4.301672284667681, 0.05 +5.854831379052524, 2.1842863255614025, -4.216717703602302, 0.05 +5.952110091192464, 1.9455742427987792, -4.140497068689801, 0.05 +6.037284983697076, 1.7034978500922517, -4.0732174549978195, 0.05 +6.110210385815255, 1.458508042363574, -4.014959996552965, 0.05 +6.170882385066493, 1.2134399850247617, -3.9290338776379152, 0.05 +6.219951758690793, 0.9813874724859951, -3.6592445114771555, 0.05 +6.258608233246484, 0.7731294911138317, -3.243666544279058, 0.05 +6.2880660035540945, 0.5891554061522151, -2.837871586115779, 0.05 +6.309558005822554, 0.42984004536919684, -2.439569756191607, 0.05 +6.324331028206878, 0.2954604476864665, -2.046806256193784, 0.05 +6.333641621662225, 0.18621186910693832, -1.6579462831041636, 0.05 +6.3387527704570585, 0.1022229758966803, -1.2716587382962423, 0.05 +6.340931287327741, 0.04357033741364273, -0.8869021444900084, 0.05 +6.341445907680765, 0.01029240706050448, -0.5029144566155819, 0.05 +6.341445907680765, 0.0, -0.15551792152192137, 0.05 diff --git a/RoboRIO/src/main/resources/calciferRightforward100InProfile.csv b/RoboRIO/src/main/resources/calciferRightforward100InProfile.csv new file mode 100644 index 00000000..5206ca4a --- /dev/null +++ b/RoboRIO/src/main/resources/calciferRightforward100InProfile.csv @@ -0,0 +1,68 @@ +67 +5.434782608695652E-4, 0.021739130434782608, 0.43478260869565216, 0.05 +0.0027173913043478243, 0.04347826086956518, 0.43478260869565144, 0.05 +0.007608695652173899, 0.09782608695652148, 1.086956521739126, 0.05 +0.016304347826086918, 0.17391304347826042, 1.5217391304347787, 0.05 +0.02989130434782601, 0.2717391304347819, 1.956521739130429, 0.05 +0.04945652173913106, 0.3913043478261009, 2.3913043478263805, 0.05 +0.07608695652174083, 0.5326086956521955, 2.8260869565218916, 0.05 +0.1108695652173944, 0.6956521739130713, 3.260869565217517, 0.05 +0.15489130434783097, 0.8804347826087313, 3.6956521739132, 0.05 +0.2092391304347897, 1.0869565217391746, 4.130434782608865, 0.05 +0.2744565217391353, 1.3043478260869124, 4.347826086954756, 0.05 +0.35054347826085114, 1.5217391304343164, 4.347826086948081, 0.05 +0.437499999999955, 1.7391304347820769, 4.347826086955209, 0.05 +0.5353260869564568, 1.956521739130036, 4.347826086959183, 0.05 +0.644021739130412, 2.1739130434791054, 4.347826086981388, 0.05 +0.7635869565217627, 2.3913043478270124, 4.34782608695814, 0.05 +0.894021739130509, 2.608695652174926, 4.347826086958273, 0.05 +1.0353260869566507, 2.826086956522833, 4.34782608695814, 0.05 +1.1874999999999856, 3.0434782608666966, 4.347826086877271, 0.05 +1.3505434782606922, 3.260869565214133, 4.347826086948725, 0.05 +1.524456521738779, 3.478260869561738, 4.3478260869521, 0.05 +1.7092391304342465, 3.6956521739093473, 4.347826086952189, 0.05 +1.9048913043470945, 3.913043478256961, 4.347826086952278, 0.05 +2.1108695652164533, 4.1195652173871755, 4.130434782604286, 0.05 +2.326086956520586, 4.304347826082653, 3.695652173909547, 0.05 +2.549456521737754, 4.467391304343362, 3.260869565214186, 0.05 +2.7798913043462194, 4.608695652169308, 2.826086956518914, 0.05 +3.0163043478242435, 4.728260869560481, 2.391304347823464, 0.05 +3.257608695650089, 4.826086956516908, 1.9565217391285472, 0.05 +3.502717391302018, 4.902173913038581, 1.5217391304334527, 0.05 +3.750543478258292, 4.956521739125481, 1.0869565217380028, 0.05 +3.9999999999971734, 4.989130434777627, 0.6521739130429083, 0.05 +4.249999999997386, 5.000000000004254, 0.21739130453255484, 0.05 +4.499637862317328, 4.992757246398831, -0.14485507210846293, 0.05 +4.748007971014006, 4.967402173933575, -0.5071014493051251, 0.05 +4.994023369565676, 4.920307971033395, -0.9418840580035948, 0.05 +5.236597101450595, 4.851474637698381, -1.376666666700288, 0.05 +5.474642210147018, 4.760902173928461, -1.8114492753984024, 0.05 +5.707071739133202, 4.64859057972367, -2.246231884095806, 0.05 +5.9327987318874, 4.514539855083957, -2.681014492794276, 0.05 +6.150736231887871, 4.358750000009426, -3.115797101490614, 0.05 +6.35979728261287, 4.1812210144999895, -3.550579710188728, 0.05 +6.558894927540653, 3.9819528985556474, -3.9853623188868426, 0.05 +6.747304347830671, 3.768188405800359, -4.275289855105768, 0.05 +6.924844202903249, 3.5507971014515682, -4.3478260869758145, 0.05 +7.091514492758385, 3.333405797102724, -4.34782608697688, 0.05 +7.247315217396082, 3.1160144927539335, -4.3478260869758145, 0.05 +7.3922463768163365, 2.8986231884050895, -4.34782608697688, 0.05 +7.526307971019151, 2.6812318840562988, -4.3478260869758145, 0.05 +7.649500000004525, 2.4638405797074725, -4.347826086976525, 0.05 +7.761822463772457, 2.2464492753586462, -4.347826086976525, 0.05 +7.86327536232295, 2.0290579710098555, -4.3478260869758145, 0.05 +7.953858695656001, 1.8116666666610115, -4.34782608697688, 0.05 +8.033572463771613, 1.5942753623122208, -4.3478260869758145, 0.05 +8.102416666669784, 1.37688405796343, -4.3478260869758145, 0.05 +8.160391304350512, 1.1594927536145505, -4.347826086977591, 0.05 +8.207858514494996, 0.9493442028896837, -4.2029710144973365, 0.05 +8.245723913045303, 0.7573079710061492, -3.8407246376706894, 0.05 +8.275074456523177, 0.5870108695574672, -3.405942028973641, 0.05 +8.29699710145036, 0.4384528985436731, -2.9711594202758818, 0.05 +8.3125788043486, 0.3116340579648025, -2.536376811577412, 0.05 +8.322906521739638, 0.20655434782074877, -2.101594202881074, 0.05 +8.32906721014522, 0.12321376811165408, -1.666811594181894, 0.05 +8.33214782608709, 0.06161231883737628, -1.232028985485556, 0.05 +8.33323532608699, 0.021749999998021963, -0.7972463767870863, 0.05 +8.333416666666666, 0.003626811593520074, -0.3624637680900378, 0.05 +8.333416666666666, 0.0, -0.07253623187040148, 0.05 diff --git a/RoboRIO/src/main/resources/calcifer_outreach_map.yml b/RoboRIO/src/main/resources/calcifer_outreach_map.yml index df23a41d..7f7164c0 100644 --- a/RoboRIO/src/main/resources/calcifer_outreach_map.yml +++ b/RoboRIO/src/main/resources/calcifer_outreach_map.yml @@ -9,14 +9,18 @@ oi: org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: '@id': overridingOi gamepad: - '@id': overridingGamepad - port: 1 + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': overridingGamepad + port: 1 rotThrottle: org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded: &overridingRotThrottle '@id': overridingRotThrottle - stick: overridingGamepad + stick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridingGamepad axis: 0 + smoothingTimeSecs: 0.04 deadband: 0.05 inverted: false fwdThrottle: @@ -27,7 +31,7 @@ oi: inverted: true invertDPad: true dPadShift: 0.1 - turnInPlaceRotScale: 0.3 + turnInPlaceRotScale: 0.6 scaleRotByFwdPoly: '@id': scaleRotByFwdPolyOverriding powerToCoefficientMap: !!map @@ -37,14 +41,18 @@ oi: org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: '@id': overridenOi gamepad: - '@id': overridenGamepad - port: 3 + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': overridenGamepad + port: 3 rotThrottle: org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded: &overridenRotThrottle '@id': overridenRotThrottle - stick: overridenGamepad + stick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridenGamepad axis: 0 + smoothingTimeSecs: 0.04 deadband: 0.05 inverted: false fwdThrottle: @@ -55,14 +63,14 @@ oi: inverted: true invertDPad: true dPadShift: 0.1 - turnInPlaceRotScale: 0.3 + turnInPlaceRotScale: 0.6 scaleRotByFwdPoly: '@id': scaleRotByFwdPolyOverriden powerToCoefficientMap: !!map 0.5: 0.6 0: 0.1 button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: '@id': overrideButton joystick: overridingGamepad buttonNumber: 6 @@ -74,7 +82,6 @@ drive: &leftMaster '@id': leftMaster port: 7 - inverted: false reverseOutput: true enableBrakeMode: false feetPerRotation: 0.9817 @@ -92,9 +99,9 @@ drive: kP: 0.3 kI: 0.0 kD: 0.0 - motionProfileP: 1.5 - motionProfileI: 0.0 - motionProfileD: 0.0 + motionProfilePFwd: 1.5 + motionProfileIFwd: 0.0 + motionProfileDFwd: 0.0 - <<: *lowGear gear: HIGH fwdNominalOutputVoltage: 1.3 @@ -116,7 +123,6 @@ drive: org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: <<: *leftMaster '@id': rightMaster - inverted: false reverseSensor: true reverseOutput: false port: 2 @@ -163,7 +169,6 @@ climber: org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: '@id': climberTalon port: 5 - inverted: false enableBrakeMode: false maxPower: 500 simpleMotor: @@ -234,6 +239,16 @@ autoStartupCommand: subsystem: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: gearHandler + - org.usfirst.frc.team449.robot.drive.commands.EnableMotors: + '@id': enableMotors + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.drive.commands.ResetPosition: + '@id': resetPosition + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive teleopStartupCommand: org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: startupCommand @@ -242,10 +257,11 @@ buttons: org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': overridingClimbButton throttle: - org.usfirst.frc.team449.robot.oi.throttles.Throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: '@id': overridingClimbButtonThrottle stick: - overridingGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridingGamepad axis: 2 triggerAt: 0.9 command: @@ -269,10 +285,11 @@ buttons: org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': overridingPushGearButton throttle: - org.usfirst.frc.team449.robot.oi.throttles.Throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: '@id': overridingPushGearThrottle stick: - overridingGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridingGamepad axis: 3 triggerAt: 0.9 command: @@ -297,10 +314,11 @@ buttons: org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': overridenClimbButton throttle: - org.usfirst.frc.team449.robot.oi.throttles.Throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: '@id': overridenClimbButtonThrottle stick: - overridenGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridenGamepad axis: 2 triggerAt: 0.9 command: @@ -324,10 +342,11 @@ buttons: org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': overridenPushGearButton throttle: - org.usfirst.frc.team449.robot.oi.throttles.Throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: '@id': overridenPushGearThrottle stick: - overridenGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + overridenGamepad axis: 3 triggerAt: 0.9 command: @@ -344,4 +363,22 @@ buttons: subsystem: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: gearHandler - action: WHEN_RELEASED \ No newline at end of file + action: WHEN_RELEASED +updater: + org.usfirst.frc.team449.robot.other.Updater: + '@id': updater + updatables: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + - org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach: + oi + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + overridenPushGearThrottle + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + overridenClimbButtonThrottle + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + overridingPushGearThrottle + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + overridingClimbButtonThrottle \ No newline at end of file diff --git a/RoboRIO/src/main/resources/forward100InProfile.csv b/RoboRIO/src/main/resources/forward100InProfile.csv new file mode 100644 index 00000000..10589984 --- /dev/null +++ b/RoboRIO/src/main/resources/forward100InProfile.csv @@ -0,0 +1,79 @@ +78 +3.712036058088627E-4, 0.014848144232354508, 0.29696288464709014, 0.05 +0.001856018029044314, 0.029696288464709023, 0.29696288464709025, 0.05 +0.00519685048132407, 0.06681664904559512, 0.7424072116177218, 0.05 +0.011136108174265857, 0.11878515385883576, 1.0393700962648127, 0.05 +0.020416198319487405, 0.1856018029044309, 1.336332980911903, 0.05 +0.03377952812860649, 0.2672665961823816, 1.6332958655590135, 0.05 +0.0519685048132415, 0.3637795336927002, 1.9302587502063728, 0.05 +0.07572553558500969, 0.4751406154353638, 2.2272216348532714, 0.05 +0.10579302765552878, 0.6013498414103818, 2.524184519500361, 0.05 +0.14291338823641653, 0.7424072116177551, 2.821147404147466, 0.05 +0.1874578209334819, 0.8908886539413075, 2.9696288464710463, 0.05 +0.2394263257467248, 1.0393700962648578, 2.9696288464710063, 0.05 +0.298818902676132, 1.1878515385881439, 2.9696288464657217, 0.05 +0.36563555172170675, 1.3363329809114954, 2.9696288464670317, 0.05 +0.4398762728834566, 1.484814423234997, 2.9696288464700293, 0.05 +0.5215410661613818, 1.633295865558505, 2.9696288464701626, 0.05 +0.6106299315555436, 1.7817773078832344, 2.9696288464945875, 0.05 +0.7071428690658853, 1.9302587502068347, 2.9696288464720055, 0.05 +0.8110798786924072, 2.078740192530437, 2.96962884647205, 0.05 +0.9224409604351091, 2.2272216348540397, 2.96962884647205, 0.05 +1.0412261142939911, 2.375703077177642, 2.96962884647205, 0.05 +1.1674353402688789, 2.524184519497754, 2.969628846402239, 0.05 +1.301068638359936, 2.6726659618211412, 2.9696288464677423, 0.05 +1.4421260085671628, 2.8211474041445372, 2.96962884646792, 0.05 +1.5906074508905592, 2.969628846467929, 2.969628846467831, 0.05 +1.7465129653301252, 3.1181102887913204, 2.969628846467831, 0.05 +1.9098425518858617, 3.2665917311147297, 2.9696288464681864, 0.05 +2.0805962105577676, 3.4150731734381212, 2.969628846467831, 0.05 +2.2587739413458436, 3.5635546157615217, 2.9696288464680087, 0.05 +2.4440045406442805, 3.7046119859687376, 2.8211474041443196, 0.05 +2.635545601241463, 3.830821211943647, 2.524184519498185, 0.05 +2.8326547159257713, 3.9421822936861695, 2.2272216348504514, 0.05 +3.0345894774855906, 4.038695231196385, 1.9302587502043167, 0.05 +3.240607478709304, 4.120360024474268, 1.633295865557649, 0.05 +3.4499663123852935, 4.18717667351979, 1.3363329809104485, 0.05 +3.661923571301942, 4.23914517833297, 1.0393700962636032, 0.05 +3.875736848247633, 4.276265538913817, 0.7424072116169356, 0.05 +4.0906637360107485, 4.298537755262322, 0.4454443269700903, 0.05 +4.305852846523989, 4.303782210264817, 0.1048891000499097, 0.05 +4.520452791718922, 4.291998903898655, -0.23566612732324188, 0.05 +4.733721164383507, 4.265367453291695, -0.5326290121391963, 0.05 +4.944915557306121, 4.2238878584522865, -0.8295918967881732, 0.05 +5.153293563275144, 4.167560119380465, -1.1265547814364396, 0.05 +5.358112775078955, 4.0963842360762115, -1.4235176660850613, 0.05 +5.558630785505931, 4.010360208539527, -1.720480550733683, 0.05 +5.754105187344454, 3.9094880367704476, -2.017443435381594, 0.05 +5.943793573382901, 3.793767720768937, -2.3144063200302156, 0.05 +6.1269535364096495, 3.6631992605349772, -2.6113692046791925, 0.05 +6.302951650069539, 3.5199622731977875, -2.864739746743794, 0.05 +6.471525691613219, 3.371480830873601, -2.9696288464837295, 0.05 +6.632675661040686, 3.2229993885493435, -2.9696288464851506, 0.05 +6.786401558351944, 3.074517946225157, -2.9696288464837295, 0.05 +6.932703383546991, 2.926036503900935, -2.96962884648444, 0.05 +7.071581136625825, 2.7775550615766953, -2.9696288464847953, 0.05 +7.20303481758845, 2.629073619252491, -2.9696288464840848, 0.05 +7.327064426434863, 2.480592176928269, -2.96962884648444, 0.05 +7.443669963165066, 2.332110734604047, -2.96962884648444, 0.05 +7.552851427779056, 2.1836292922798073, -2.9696288464847953, 0.05 +7.654608820276835, 2.0351478499555853, -2.96962884648444, 0.05 +7.748942140658404, 1.8866664076313633, -2.96962884648444, 0.05 +7.835851388923762, 1.7381849653071768, -2.9696288464837295, 0.05 +7.915336565072909, 1.589703522982937, -2.9696288464847953, 0.05 +7.987397669105845, 1.441222080658715, -2.96962884648444, 0.05 +8.052034701022569, 1.2927406383344753, -2.9696288464847953, 0.05 +8.109247660823083, 1.1442591960102888, -2.9696288464837295, 0.05 +8.159036548507387, 0.9957777536860846, -2.9696288464840848, 0.05 +8.201401364075478, 0.8472963113618093, -2.969628846485506, 0.05 +8.236451088383818, 0.700994486166806, -2.9260365039000646, 0.05 +8.264665905894674, 0.5642963502171128, -2.7339627189938653, 0.05 +8.286788223819668, 0.4424463584998861, -2.436999834344533, 0.05 +8.303560449370421, 0.335444511015055, -2.140036949696622, 0.05 +8.315724989758554, 0.243290807762655, -1.8430740650480004, 0.05 +8.324024252195688, 0.16598524874268605, -1.5461111803993788, 0.05 +8.329200643893447, 0.10352783395518372, -1.2491482957500466, 0.05 +8.331996572063447, 0.055918563400005894, -0.9521854111035566, 0.05 +8.333154443917314, 0.0231574370773302, -0.6552225264535139, 0.05 +8.333416666666665, 0.005244454987014535, -0.3582596418063133, 0.05 +8.333416666666665, 0.0, -0.1048890997402907, 0.05 diff --git a/RoboRIO/src/main/resources/forwardProfile.csv b/RoboRIO/src/main/resources/forwardProfile.csv deleted file mode 100644 index 62bc919c..00000000 --- a/RoboRIO/src/main/resources/forwardProfile.csv +++ /dev/null @@ -1,133 +0,0 @@ -132 -3.7374135544680597E-4, 0.014949654217872237, 0.05, -0.00186870677723403, 0.02989930843574448, 0.05, -0.00523237897625528, 0.067273443980425, 0.05, -0.011212240663404156, 0.11959723374297754, 0.05, -0.02055577454957428, 0.18687067772340243, 0.05, -0.03363672199021245, 0.2616189488127634, 0.05, -0.05045508298531868, 0.3363672199021246, 0.05, -0.07101085753489349, 0.41111549099149614, 0.05, -0.09530404563893688, 0.48586376208086784, 0.05, -0.12333464729744846, 0.5606120331702316, 0.05, -0.15510266251042826, 0.6353603042595962, 0.05, -0.19060809127787626, 0.71010857534896, 0.05, -0.2298509335997925, 0.7848568464383249, 0.05, -0.27283118947617696, 0.8596051175276892, 0.05, -0.31954885890702955, 0.9343533886170519, 0.05, -0.3700039418923504, 1.0091016597064173, 0.05, -0.4241964384321395, 1.0838499307957816, 0.05, -0.48212634852639213, 1.1585982018850527, 0.05, -0.5437936721750961, 1.2333464729740795, 0.05, -0.6091984093782672, 1.3080947440634216, 0.05, -0.6783405601359052, 1.3828430151527593, 0.05, -0.7512201244480099, 1.4575912862420948, 0.05, -0.8278371023145817, 1.532339557331437, 0.05, -0.9081914937356204, 1.6070878284207724, 0.05, -0.992283298711164, 1.6818360995108739, 0.05, -1.0801125172411976, 1.756584370600669, 0.05, -1.1716791493257008, 1.8313326416900644, 0.05, -1.2669831949646733, 1.9060809127794487, 0.05, -1.3660246541581151, 1.9808291838688374, 0.05, -1.4688035269060267, 2.0555774549582306, 0.05, -1.5753198132084076, 2.1303257260476194, 0.05, -1.6855735130652583, 2.2050739971370126, 0.05, -1.7995646264765783, 2.2798222682264013, 0.05, -1.917293153442309, 2.3545705393146132, 0.05, -2.038759093962399, 2.4293188104017993, 0.05, -2.163962448036954, 2.5040670814910992, 0.05, -2.2929032156659725, 2.5788153525803725, 0.05, -2.425581396849456, 2.6535636236696725, 0.05, -2.5619969915874035, 2.7283118947589458, 0.05, -2.7021499998798153, 2.803060165848237, 0.05, -2.846040421726692, 2.8778084369375367, 0.05, -2.9936682571280326, 2.95255670802681, 0.05, -3.145033506083838, 3.02730497911611, 0.05, -3.3001361685941073, 3.1020532502053833, 0.05, -3.458976244658841, 3.1768015212946743, 0.05, -3.6215537342780397, 3.2515497923839742, 0.05, -3.7878686374517017, 3.3262980634732386, 0.05, -3.9579209541798277, 3.401046334562521, 0.05, -4.131710684462419, 3.4757946056518385, 0.05, -4.309237828299475, 3.550542876741112, 0.05, -4.490502385690994, 3.625291147830385, 0.05, -4.675504356636977, 3.7000394189196584, 0.05, -4.864243741137425, 3.774787690008967, 0.05, -5.056720539192338, 3.8495359610982582, 0.05, -5.252934750801715, 3.9242842321875315, 0.05, -5.452886375965556, 3.9990325032768226, 0.05, -5.656575414683861, 4.073780774366096, 0.05, -5.86400186695663, 4.148529045455387, 0.05, -6.075165732783864, 4.223277316544678, 0.05, -6.290067012165562, 4.298025587633969, 0.05, -6.508705705101726, 4.372773858723278, 0.05, -6.730708070236906, 4.440047302703594, 0.05, -6.955326624860212, 4.492371092466119, 0.05, -7.18181388626075, 4.529745228010764, 0.05, -7.4094223717276275, 4.552169709337548, 0.05, -7.6373280789272435, 4.55811414399232, 0.05, -7.864707005524972, 4.547578531954564, 0.05, -8.09081166880941, 4.522093265688767, 0.05, -8.314894586069668, 4.481658345205162, 0.05, -8.53620827459484, 4.426273770503428, 0.05, -8.754081771297505, 4.357469934053313, 0.05, -8.968217854445687, 4.282721662963631, 0.05, -9.178616524039382, 4.207973391873914, 0.05, -9.385277780078594, 4.133225120784232, 0.05, -9.588201622563316, 4.0584768496944434, 0.05, -9.78738805149356, 3.983728578604868, 0.05, -9.982837066869314, 3.9089803075150797, 0.05, -10.174548668690585, 3.8342320364254334, 0.05, -10.36252285695737, 3.7594837653356805, 0.05, -10.54675963166967, 3.6847354942459987, 0.05, -10.727258992827483, 3.6099872231562813, 0.05, -10.904020940430813, 3.5352389520665994, 0.05, -11.077045474479657, 3.460490680976882, 0.05, -11.246332594974017, 3.3857424098872, 0.05, -11.411882301913892, 3.310994138797483, 0.05, -11.573694595299282, 3.236245867707801, 0.05, -11.731769475130186, 3.1614975966180836, 0.05, -11.886106941406606, 3.0867493255284018, 0.05, -12.03670699412854, 3.0120010544386844, 0.05, -12.183569633295987, 2.9372527833489315, 0.05, -12.326694858908953, 2.8625045122593207, 0.05, -12.46608267096743, 2.7877562411695322, 0.05, -12.601733069471424, 2.713007970079886, 0.05, -12.73364605442093, 2.638259698990133, 0.05, -12.861821625815956, 2.563511427900522, 0.05, -12.986259783656495, 2.4887631568107693, 0.05, -13.106960527942546, 2.4140148857210164, 0.05, -13.223923858674116, 2.3392666146314056, 0.05, -13.337149775851202, 2.2645183435417238, 0.05, -13.446638279473799, 2.1897700724519353, 0.05, -13.552389369541913, 2.115021801362289, 0.05, -13.654403046055544, 2.040273530272607, 0.05, -13.752679309014688, 1.9655252591828898, 0.05, -13.847218158419345, 1.8907769880931369, 0.05, -13.938019594269521, 1.816028717003526, 0.05, -14.02508361656521, 1.7412804459137732, 0.05, -14.108410225306413, 1.6665321748240558, 0.05, -14.187999420493133, 1.5917839037344095, 0.05, -14.263851202125364, 1.517035632644621, 0.05, -14.335965570203113, 1.4422873615549747, 0.05, -14.404342524726376, 1.3675390904652573, 0.05, -14.468982065695153, 1.29279081937554, 0.05, -14.529884193109448, 1.2180425482858936, 0.05, -14.587048906969255, 1.1432942771961407, 0.05, -14.640476207274578, 1.068546006106459, 0.05, -14.690166094025415, 0.9937977350167415, 0.05, -14.736118567221768, 0.9190494639270597, 0.05, -14.778333626863635, 0.8443011928373423, 0.05, -14.816811272951016, 0.7695529217476249, 0.05, -14.851551505483915, 0.6948046506579786, 0.05, -14.882554324462326, 0.6200563795682257, 0.05, -14.909819729886253, 0.5453081084785438, 0.05, -14.933347721755696, 0.470559837388862, 0.05, -14.953138300070654, 0.3958115662991446, 0.05, -14.969191464831125, 0.3210632952094272, 0.05, -14.98150721603711, 0.24631502411970985, 0.05, -14.990162073312083, 0.17309714549945454, 0.05, -14.995606297634962, 0.10888448645758331, 0.05, -14.998587371716644, 0.05962148163362713, 0.05, -14.999852778268025, 0.025308131027621528, 0.05, -15.00015, 0.005944434639495455, 0.05, -15.00015, 0.0, 0.05, diff --git a/RoboRIO/src/main/resources/nate_map.yml b/RoboRIO/src/main/resources/nate_map.yml new file mode 100644 index 00000000..2f8494be --- /dev/null +++ b/RoboRIO/src/main/resources/nate_map.yml @@ -0,0 +1,741 @@ +--- +doMP: true +testMP: false +leftTestProfile: + &leftTest + '@id': leftTest + filename: "forward100InProfile.csv" + inverted: false +rightTestProfile: + <<: *leftTest + '@id': rightTest +leftProfiles: !!map + "blue_center" : + '@id': blueLeftCenter + filename: "calciferLeftBlueMidProfile.csv" + inverted: false + "blue_left" : + '@id': blueLeftLeft + filename: "calciferLeftBlueLeftProfile.csv" + inverted: false + "blue_right" : + '@id': blueLeftRight + filename: "calciferLeftBlueRightProfile.csv" + inverted: false + "red_center" : + '@id': redLeftCenter + filename: "calciferLeftRedMidProfile.csv" + inverted: false + "red_left" : + '@id': redLeftLeft + filename: "calciferLeftRedLeftProfile.csv" + inverted: false + "red_right" : + '@id': redLeftRight + filename: "calciferLeftRedRightProfile.csv" + inverted: false +rightProfiles: !!map + "blue_center" : + '@id': blueRightCenter + filename: "calciferRightBlueMidProfile.csv" + inverted: false + "blue_left" : + '@id': blueRightLeft + filename: "calciferRightBlueLeftProfile.csv" + inverted: false + "blue_right" : + '@id': blueRightRight + filename: "calciferRightBlueRightProfile.csv" + inverted: false + "red_center" : + '@id': redRightCenter + filename: "calciferRightRedMidProfile.csv" + inverted: false + "red_left" : + '@id': redRightLeft + filename: "calciferRightRedLeftProfile.csv" + inverted: false + "red_right" : + '@id': redRightRight + filename: "calciferRightRedRightProfile.csv" + inverted: false +allianceSwitch: + '@id': allianceSwitch + ports: [3] +dropGearSwitch: + '@id': dropGearSwitch + ports: [2] +locationDial: + '@id': locationDial + ports: [0, 1] +RIOduinoPort: 4 +oi: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + '@id': oi + gamepad: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': driverGamepad + port: 1 + rotThrottle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial: + &rotThrottle + '@id': rotThrottle + stick: driverGamepad + axis: 0 + smoothingTimeSecs: 0.04 + deadband: 0.05 + inverted: false + polynomial: + '@id': rotPoly + powerToCoefficientMap: !!map + 2 : 1 + fwdThrottle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum: + '@id': fwdThrottle + throttles: + - org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial: + <<: *rotThrottle + '@id': fwdTrigger + axis: 3 + inverted: false + polynomial: + '@id': fwdPoly + powerToCoefficientMap: !!map + 2 : 1 + - org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial: + <<: *rotThrottle + '@id': revTrigger + axis: 2 + inverted: true + polynomial: + '@id': revPoly + powerToCoefficientMap: !!map + 2 : 1 + invertDPad: false + dPadShift: 0.1 + turnInPlaceRotScale: 0.5 + scaleRotByFwdPoly: + '@id': scaleRotByFwdPoly + powerToCoefficientMap: !!map + 0.5: 0.6 + 0: 0.2 +drive: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + '@id': drive + leftMaster: + org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + &leftMaster + '@id': leftMaster + port: 7 + reverseOutput: true + enableBrakeMode: false + feetPerRotation: 0.9817 + currentLimit: 40 + feedbackDevice: QuadEncoder + encoderCPR: 512 + reverseSensor: false + startingGear: LOW + perGearSettings: + - &lowGear + gear: LOW + fwdPeakOutputVoltage: 12 + fwdNominalOutputVoltage: 0.7 + maxSpeed: 6.2 + kP: 0.5 + kI: 0.0 + kD: 0.0 + motionProfilePFwd: 1.5 + motionProfileIFwd: 0.0 + motionProfileDFwd: 0.0 + - <<: *lowGear + gear: HIGH + fwdNominalOutputVoltage: 1.3 + maxSpeed: 15.71 + kP: 0.7 + kI: 0.0 + kD: 3.0 + updaterProcessPeriodSecs: 0.005 + minNumPointsInBottomBuffer: 10 + slaves: + - '@id': talon8 + port: 8 + inverted: true + - '@id': talon6 + port: 6 + inverted: true + rightMaster: + org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + <<: *leftMaster + '@id': rightMaster + reverseSensor: true + reverseOutput: false + port: 2 + slaves: + - '@id': talon1 + port: 1 + inverted: true + - '@id': talon3 + port: 3 + inverted: true + VelScale: 0.9 + navX: + '@id': driveNavX + port: kMXP + shiftComponent: + org.usfirst.frc.team449.robot.components.ShiftComponent: + '@id': driveShiftComponent + otherShiftables: + - org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + leftMaster + - org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + rightMaster + piston: + '@id': driveShifter + module: 15 + forward: 2 + reverse: 3 + lowGearPistonPos: kForward + startingGear: LOW +defaultDriveCommand: + org.usfirst.frc.team449.robot.commands.multiInterface.drive.UnidirectionalNavXShiftingDefaultDrive: + '@id': defaultDriveCommand + kP: 0.003 + kI: 0.0 + kD: 0.0 + absoluteTolerance: 0 + toleranceBuffer: 25 + deadband: 2 + maxAngularVelToEnterLoop: 0.05 + inverted: true + highGearAngularCoefficient: 2 + driveStraightLoopEntryTimer: + '@id': driveStraightLoopEntryTimer + bufferTimeSeconds: 0.15 + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + oi: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi + autoshiftComponent: + '@id': autoshiftComponent + upshiftSpeed: 4 + downshiftSpeed: 2 + upshiftBufferTimer: + '@id': upshiftBufferTimer + bufferTimeSeconds: 0.25 + downshiftBufferTimer: + '@id': downshiftBufferTimer + bufferTimeSeconds: 0.0 + upshiftFwdThresh: 0.3 +climber: + org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + '@id': climber + talonSRX: + org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon: + '@id': climberTalon + port: 5 + enableBrakeMode: false + maxPower: 500 + simpleMotor: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedVictor: + '@id': climberVictor + port: 0 + inverted: false + powerLimitTimer: + '@id': powerLimitTimer + bufferTimeSeconds: 0.005 +gearHandler: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: + '@id': gearHandler + piston: + '@id': gearHandlerPiston + module: 15 + forward: 4 + reverse: 5 +camera: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork: + '@id': cameras + serverPort: 1180 + serverName: "Cameras" + cameras: + - '@id': cam0 + name: "cam0" + devAddress: 0 + width: 200 + height: 112 + fps: 30 +pneumatics: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + '@id': pneumatics + nodeID: 15 + pressureSensor: + '@id': pressureSensor + port: 0 + oversampleBits: 0 + averageBits: 0 +logger: + '@id': logger + subsystems: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + pneumatics + - org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + '@id': poseEstimator + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + absolutePosAngleTolerance: 5 + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi + loopTimeSecs: 0.05 + eventLogFilename: "/home/lvuser/logs/eventLog-" + telemetryLogFilename: "/home/lvuser/logs/telemetryLog-" +centerAuto: + org.usfirst.frc.team449.robot.commands.autonomous.Auto2017Center: + '@id': centerAuto + runWallToPegProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.commands.RunLoadedProfile: + &runLoadedProfile + '@id': runCenterWallToPegProfile + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + timeout: 10 + require: true + dropGear: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidReverse: + &openGearHandler + '@id': centerOpenGearHandlerCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: + gearHandler + dropGearSwitch: + dropGearSwitch + driveBack: + org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed: + '@id': driveBackCommand + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + velocity: -0.5 + seconds: 0.5 +boilerAuto: + org.usfirst.frc.team449.robot.commands.autonomous.Auto2017Feeder: + '@id': boilerAuto + runWallToPegProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.commands.RunLoadedProfile: + <<: *runLoadedProfile + '@id': runBoilerPegToWallProfile + dropGear: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidReverse: + <<: *openGearHandler + '@id': boilerOpenGearHandler + dropGearSwitch: + dropGearSwitch + allianceSwitch: + allianceSwitch + runRedBackupProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': runRedBackupProfileBoiler + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + #Yes, this is the "right" profile. For inverted profiles, you also have to switch the sides. + '@id': redLeftBackupBoiler + filename: "calciferRightBlueBackupProfile.csv" + inverted: true + right: + '@id': redRightBackupBoiler + filename: "calciferLeftBlueBackupProfile.csv" + inverted: true + timeout: 10 + runBlueBackupProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': runBlueBackupProfileBoiler + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + #Yes, this is the "right" profile. For inverted profiles, you also have to switch the sides. + '@id': blueLeftBackupBoiler + filename: "calciferRightRedBackupProfile.csv" + inverted: true + right: + '@id': blueRightBackupBoiler + filename: "calciferLeftRedBackupProfile.csv" + inverted: true + timeout: 10 + driveForwardsRed: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': driveForwardsMPBoilerRed + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + '@id': leftForwardsProfileBoilerRed + filename: "calciferLeftRedBoilerToLoadingProfile.csv" + inverted: false + right: + '@id': rightForwardsProfileBoilerRed + filename: "calciferRightRedBoilerToLoadingProfile.csv" + inverted: false + timeout: 10 + driveForwardsBlue: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': driveForwardsMPBoilerBlue + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + '@id': leftForwardsProfileBoilerBlue + filename: "calciferLeftBlueBoilerToLoadingProfile.csv" + inverted: false + right: + '@id': rightForwardsProfileBoilerBlue + filename: "calciferRightBlueBoilerToLoadingProfile.csv" + inverted: false + timeout: 10 + waitBetweenProfilesMillis: 50 +feederAuto: + org.usfirst.frc.team449.robot.commands.autonomous.Auto2017Feeder: + '@id': feederAuto + runWallToPegProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.commands.RunLoadedProfile: + <<: *runLoadedProfile + '@id': runFeederWallToPegProfile + dropGear: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidReverse: + <<: *openGearHandler + '@id': feederOpenGearHandler + dropGearSwitch: + dropGearSwitch + allianceSwitch: + allianceSwitch + runRedBackupProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': runRedBackupProfile + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + #Yes, this is the "right" profile. For inverted profiles, you also have to switch the sides. + '@id': redLeftBackup + filename: "calciferRightRedBackupProfile.csv" + inverted: true + right: + '@id': redRightBackup + filename: "calciferLeftRedBackupProfile.csv" + inverted: true + timeout: 10 + runBlueBackupProfile: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': runBlueBackupProfile + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + #Yes, this is the "right" profile. For inverted profiles, you also have to switch the sides. + '@id': blueLeftBackup + filename: "calciferRightBlueBackupProfile.csv" + inverted: true + right: + '@id': blueRightBackup + filename: "calciferLeftBlueBackupProfile.csv" + inverted: true + timeout: 10 + driveForwardsRed: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': driveForwardsMPRed + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + '@id': leftForwardsProfileFeederRed + filename: "calciferLeftRedLoadingToLoadingProfile.csv" + inverted: false + right: + '@id': rightForwardsProfileFeederRed + filename: "calciferRightRedLoadingToLoadingProfile.csv" + inverted: false + timeout: 10 + driveForwardsBlue: + org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.TwoSideMPSubsystem.commands.RunProfileTwoSides: + '@id': driveForwardsMPBlue + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + left: + '@id': leftForwardsProfileFeederBlue + filename: "calciferLeftBlueLoadingToLoadingProfile.csv" + inverted: false + right: + '@id': rightForwardsProfileFeederBlue + filename: "calciferRightBlueLoadingToLoadingProfile.csv" + inverted: false + timeout: 10 + waitBetweenProfilesMillis: 50 +nonMPAutoCommand: + org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineNominalVoltage: + '@id': determineNominalVoltage + minSpeed: 0.1 + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive +autoStartupCommand: + org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: + '@id': startModeCommand + commandSet: + - org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToLowGear: + '@id': startupSwitchToLowCommand + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.commands.StartCompressor: + '@id': startCompressor + subsystem: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.pneumatics.Pneumatics: + pneumatics + - org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidForward: + '@id': closeGearHandlerStartup + subsystem: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: + gearHandler + - org.usfirst.frc.team449.robot.drive.commands.EnableMotors: + '@id': enableMotors + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.drive.commands.ResetPosition: + '@id': resetPosition + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive +teleopStartupCommand: + org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: + startModeCommand +startupCommand: + org.usfirst.frc.team449.robot.commands.general.RunRunnables: + '@id': runRunnables + runnables: + - org.usfirst.frc.team449.robot.components.NavXRumbleComponent: + '@id': rumbleComponent + navX: + driveNavX + rumbleables: + - org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + - org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': gunnerGamepad + port: 3 + minJerk: 804 + maxJerk: 2412 + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + poseEstimator +buttons: + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + '@id': switchToLowButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + angle: 180 + command: + org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToLowGear: + '@id': switchToLowCommand + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + switchToLowButton + command: + org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift: + '@id': overrideShifting + drive: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + override: true + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + switchToLowButton + command: + org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift: + '@id': unoverrideShifting + drive: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + override: false + action: WHEN_RELEASED + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + '@id': switchToHighButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + angle: 0 + command: + org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToHighGear: + '@id': switchToHighCommand + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + switchToHighButton + command: + org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift: + overrideShifting + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.dPadButton: + switchToHighButton + command: + org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift: + unoverrideShifting + action: WHEN_RELEASED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': overrideNavXButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + buttonNumber: 1 + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX: + '@id': overrideNavXCommand + override: true + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + overrideNavXButton + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX: + '@id': unoverrideNavXCommand + override: false + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + action: WHEN_RELEASED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': jiggleRobotButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + buttonNumber: 8 + command: + org.usfirst.frc.team449.robot.commands.multiInterface.drive.JiggleRobot: + '@id': jiggleRobotCommand + kP: 0.007 + kI: 0.0 + kD: 0.0 + toleranceBuffer: 25 + absoluteTolerance: 1 + deadband: 0.75 + inverted: false + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': climbButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + buttonNumber: 2 + command: + org.usfirst.frc.team449.robot.commands.multiInterface.RunMotorWhileConditonMet: + '@id': climbCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + climbButton + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOffWithRequires: + '@id': stopClimbCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + action: WHEN_RELEASED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': manualClimbButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + buttonNumber: 3 + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOn: + '@id': manualClimbCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + manualClimbButton + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOffWithRequires: + stopClimbCommand + action: WHEN_RELEASED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': switchCameraButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad + buttonNumber: 9 + command: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.commands.ChangeCam: + '@id': switchCameraCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork: + cameras + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + '@id': pushGearButton + joystick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + buttonNumber: 1 + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidReverse: + <<: *openGearHandler + '@id': openGearHandlerCommand + action: WHEN_PRESSED + - button: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: + pushGearButton + command: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidForward: + '@id': closeGearHandlerCommand + subsystem: + org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: + gearHandler + action: WHEN_RELEASED +updater: + org.usfirst.frc.team449.robot.other.Updater: + '@id': updater + updatables: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi \ No newline at end of file diff --git a/RoboRIO/src/main/resources/calcifer_map.yml b/RoboRIO/src/main/resources/naveen_map.yml similarity index 81% rename from RoboRIO/src/main/resources/calcifer_map.yml rename to RoboRIO/src/main/resources/naveen_map.yml index 9a424d3a..f66bc190 100644 --- a/RoboRIO/src/main/resources/calcifer_map.yml +++ b/RoboRIO/src/main/resources/naveen_map.yml @@ -4,7 +4,7 @@ testMP: false leftTestProfile: &leftTest '@id': leftTest - filename: "100InchProfile.csv" + filename: "forward100InProfile.csv" inverted: false rightTestProfile: <<: *leftTest @@ -70,35 +70,45 @@ locationDial: ports: [0, 1] RIOduinoPort: 4 oi: - org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOrientedPosCos: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: '@id': oi - xThrottle: + gamepad: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': driverGamepad + port: 1 + rotThrottle: org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial: - &xThrottle - '@id': xThrottle - stick: - '@id': driverGamepad - port: 1 - axis: 1 - deadband: 0.02 - inverted: true + &rotThrottle + '@id': rotThrottle + stick: driverGamepad + axis: 0 + deadband: 0.05 + smoothingTimeSecs: 0.04 + inverted: false polynomial: '@id': rotPoly powerToCoefficientMap: !!map 2 : 1 - yThrottle: + fwdThrottle: org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial: - <<: *xThrottle - '@id': yThrottle - axis: 0 + <<: *rotThrottle + '@id': fwdThrottle + axis: 5 stick: driverGamepad - inverted: false + inverted: true polynomial: '@id': fwdPoly powerToCoefficientMap: !!map 2 : 1 - rDeadband: 0.1 + invertDPad: false + dPadShift: 0.1 + turnInPlaceRotScale: 0.5 + scaleRotByFwdPoly: + '@id': scaleRotByFwdPoly + powerToCoefficientMap: !!map + 0.5: 0.6 + 0: 0.2 drive: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: '@id': drive @@ -124,9 +134,9 @@ drive: kP: 0.5 kI: 0.0 kD: 0.0 - motionProfileP: 1.5 - motionProfileI: 0.0 - motionProfileD: 0.0 + motionProfilePFwd: 1.5 + motionProfileIFwd: 0.0 + motionProfileDFwd: 0.0 - <<: *lowGear gear: HIGH fwdNominalOutputVoltage: 1.3 @@ -177,31 +187,26 @@ drive: lowGearPistonPos: kForward startingGear: LOW defaultDriveCommand: - org.usfirst.frc.team449.robot.commands.multiInterface.drive.FieldOrientedUnidirectionalDriveCommandShifting: + org.usfirst.frc.team449.robot.commands.multiInterface.drive.UnidirectionalNavXShiftingDefaultDrive: '@id': defaultDriveCommand - kP: 0.005 + kP: 0.003 kI: 0.0 kD: 0.0 absoluteTolerance: 0 + toleranceBuffer: 25 deadband: 2 + maxAngularVelToEnterLoop: 0.05 inverted: true highGearAngularCoefficient: 2 + driveStraightLoopEntryTimer: + '@id': driveStraightLoopEntryTimer + bufferTimeSeconds: 0.15 subsystem: org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: drive oi: - org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOrientedPosCos: + org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: oi - snapPoints: - - snapTo: 0 - upperBound: 10 - lowerBound: -10 - - snapTo: 60 - upperBound: 70 - lowerBound: 50 - - snapTo: -60 - upperBound: -50 - lowerBound: -70 autoshiftComponent: '@id': autoshiftComponent upshiftSpeed: 4 @@ -230,32 +235,6 @@ climber: powerLimitTimer: '@id': powerLimitTimer bufferTimeSeconds: 0.005 -#multiSubsystem: -# org.usfirst.frc.team449.robot.subsystem.complexooter.LoggingShooter: -# '@id': multiSubsystem -# shooterTalon: -# '@id': shooterTalon -# port: 4 -# inverted: false -# reverseSensor: true -# enableBrakeMode: false -# fwdPeakOutputVoltage: 12 -# fwdNominalOutputVoltage: 0 -# closedLoopRampRate: 12 -# maxClosedLoopVoltage: 12 -# feedbackDevice: QuadEncoder -# encoderCPR: 1024 -# maxSpeedHigh: 90 -# highGearP: 0.15 -# highGearI: 0.0 -# highGearD: 0.0 -# shooterThrottle: 0.72 -# spinUpTimeSecs: 1 -# feederVictor: -# '@id': feederVictor -# port: 1 -# inverted: true -# feederThrottle: 0.66 gearHandler: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: '@id': gearHandler @@ -267,7 +246,7 @@ gearHandler: camera: org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork: '@id': cameras - serverPort: 5800 + serverPort: 1180 serverName: "Cameras" cameras: - '@id': cam0 @@ -294,8 +273,14 @@ logger: pneumatics - org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: climber -# - org.usfirst.frc.team449.robot.subsystem.complexooter.LoggingShooter: -# multiSubsystem + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + '@id': poseEstimator + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + absolutePosAngleTolerance: 5 + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi loopTimeSecs: 0.05 eventLogFilename: "/home/lvuser/logs/eventLog-" telemetryLogFilename: "/home/lvuser/logs/telemetryLog-" @@ -493,7 +478,7 @@ nonMPAutoCommand: drive autoStartupCommand: org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: - '@id': startupCommand + '@id': startModeCommand commandSet: - org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToLowGear: '@id': startupSwitchToLowCommand @@ -510,16 +495,44 @@ autoStartupCommand: subsystem: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: gearHandler + - org.usfirst.frc.team449.robot.drive.commands.EnableMotors: + '@id': enableMotors + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.drive.commands.ResetPosition: + '@id': resetPosition + subsystem: + org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive teleopStartupCommand: org.usfirst.frc.team449.robot.commands.general.ParallelCommandGroup: - startupCommand + startModeCommand +startupCommand: + org.usfirst.frc.team449.robot.commands.general.RunRunnables: + '@id': runRunnables + runnables: + - org.usfirst.frc.team449.robot.components.NavXRumbleComponent: + '@id': rumbleComponent + navX: + driveNavX + rumbleables: + - org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + - org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + '@id': gunnerGamepad + port: 3 + minJerk: 804 + maxJerk: 2412 + - org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator: + poseEstimator buttons: - button: org.usfirst.frc.team449.robot.oi.buttons.dPadButton: '@id': switchToLowButton joystick: - '@id': gunnerGamepad - port: 3 + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad angle: 180 command: org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToLowGear: @@ -554,7 +567,8 @@ buttons: org.usfirst.frc.team449.robot.oi.buttons.dPadButton: '@id': switchToHighButton joystick: - gunnerGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad angle: 0 command: org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.SwitchToHighGear: @@ -578,10 +592,11 @@ buttons: unoverrideShifting action: WHEN_RELEASED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: '@id': overrideNavXButton joystick: - gunnerGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad buttonNumber: 1 command: org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX: @@ -592,7 +607,7 @@ buttons: drive action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: overrideNavXButton command: org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX: @@ -603,10 +618,11 @@ buttons: drive action: WHEN_RELEASED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: '@id': jiggleRobotButton joystick: - gunnerGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad buttonNumber: 8 command: org.usfirst.frc.team449.robot.commands.multiInterface.drive.JiggleRobot: @@ -623,11 +639,16 @@ buttons: drive action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': climbButton - joystick: - driverGamepad - buttonNumber: 2 + throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + '@id': climbButtonThrottle + stick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + axis: 2 + triggerAt: 0.9 command: org.usfirst.frc.team449.robot.commands.multiInterface.RunMotorWhileConditonMet: '@id': climbCommand @@ -636,7 +657,7 @@ buttons: climber action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: climbButton command: org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOffWithRequires: @@ -646,10 +667,11 @@ buttons: climber action: WHEN_RELEASED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: '@id': manualClimbButton joystick: - gunnerGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad buttonNumber: 3 command: org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOn: @@ -659,17 +681,18 @@ buttons: climber action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: manualClimbButton command: org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.commands.TurnMotorOffWithRequires: stopClimbCommand action: WHEN_RELEASED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: '@id': switchCameraButton joystick: - gunnerGamepad + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + gunnerGamepad buttonNumber: 9 command: org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.commands.ChangeCam: @@ -679,18 +702,23 @@ buttons: cameras action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.TriggerButton: '@id': pushGearButton - joystick: - driverGamepad - buttonNumber: 1 + throttle: + org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + '@id': pushGearThrottle + stick: + org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick: + driverGamepad + axis: 3 + triggerAt: 0.9 command: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidReverse: <<: *openGearHandler '@id': openGearHandlerCommand action: WHEN_PRESSED - button: - org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: + org.usfirst.frc.team449.robot.oi.buttons.SimpleButton: pushGearButton command: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.commands.SolenoidForward: @@ -699,46 +727,17 @@ buttons: org.usfirst.frc.team449.robot.subsystem.interfaces.solenoid.SolenoidSimple: gearHandler action: WHEN_RELEASED -# - button: -# org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: -# '@id': fireShooterButton -# joystick: -# gunnerGamepad -# buttonNumber: 6 -# command: -# org.usfirst.frc.team449.robot.commands.multiSubsystembsystem.FireShooter: -# '@id': fireShooterCommand -# shooter: -# org.usfirst.frc.team449.robot.subsystem.complexooter.LoggingShooter: -# multiSubsystem -# action: WHEN_PRESSED -# - button: -# org.usfirstfirst.frc.team449.robot.oi.buttons.TriggerButton: -# '@id': rackShooterButton -# throttle: -# '@id': rackShooterThrottle -# org.usfirst.frc.team449.robot.oi.throttles.Throttle: -# stick: -# gunnerGamepad -# axis: 3 -# triggerAt: 0.9 -# command: -# org.usfirst.frc.team449.robot.commands.multiSubsystembsystem.RackShooter: -# '@id': rackShooterCommand -# shooter: -# org.usfirst.frc.team449.robot.subsystem.complexooter.LoggingShooter: -# multiSubsystem -# action: WHEN_PRESSED -# - button: -# org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton: -# '@id': resetShooterButton -# joystick: -# gunnerGamepad -# buttonNumber: 5 -# command: -# org.usfirst.frc.team449.robot.commands.multiSubsystembsystem.ResetShooter: -# '@id': resetShooterCommand -# shooter: -# org.usfirst.frc.team449.robot.subsystem.complexooter.LoggingShooter: -# multiSubsystem -# action: WHEN_PRESSED \ No newline at end of file +updater: + org.usfirst.frc.team449.robot.other.Updater: + '@id': updater + updatables: + - org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable: + drive + - org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited: + climber + - org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad: + oi + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + pushGearThrottle + - org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic: + climbButtonThrottle \ No newline at end of file diff --git a/scripts/getLogs.sh b/bash scripts/getLogs.sh similarity index 100% rename from scripts/getLogs.sh rename to bash scripts/getLogs.sh diff --git a/scripts/smartdashboard.sh b/bash scripts/smartdashboard.sh similarity index 100% rename from scripts/smartdashboard.sh rename to bash scripts/smartdashboard.sh diff --git a/docs/allclasses-frame.html b/docs/allclasses-frame.html index 1aaffbde..137c6154 100644 --- a/docs/allclasses-frame.html +++ b/docs/allclasses-frame.html @@ -2,9 +2,9 @@ - + All Classes (RoboRIO 1.0 API) - + @@ -25,6 +25,7 @@

All Classes

  • CommandButton
  • CommandSequence
  • DetermineNominalVoltage
  • +
  • DetermineVelVsVoltage
  • dPadButton
  • DriveAtSpeed
  • DriveShiftable
  • @@ -34,8 +35,7 @@

    All Classes

  • DriveTalonClusterShiftable
  • DriveUnidirectional
  • DriveUnidirectionalSimple
  • -
  • FactoryButton
  • -
  • FactoryJoystickButton
  • +
  • EnableMotors
  • FieldOrientedUnidirectionalDriveCommand
  • FieldOrientedUnidirectionalDriveCommand.AngularSnapPoint
  • FieldOrientedUnidirectionalDriveCommandShifting
  • @@ -54,13 +54,16 @@

    All Classes

  • Logger
  • LoggingShooter
  • MappedAHRS
  • +
  • MappedButton
  • MappedDigitalInput
  • MappedDoubleSolenoid
  • MappedJoystick
  • +
  • MappedRunnable
  • MappedUsbCamera
  • MappedVictor
  • MotionProfileData
  • NavXDriveStraight
  • +
  • NavXRumbleComponent
  • NavXTurnToAngle
  • NavXTurnToAngleRelative
  • OI
  • @@ -83,13 +86,16 @@

    All Classes

  • Polynomial
  • PressureSensor
  • RackShooter
  • +
  • ResetPosition
  • ResetShooter
  • Robot
  • RobotMap2017
  • +
  • Rumbleable
  • RunLoadedProfile
  • RunMotorWhileConditonMet
  • RunProfile
  • RunProfileTwoSides
  • +
  • RunRunnables
  • SetIntakeMode
  • Shiftable
  • Shiftable.gear
  • @@ -97,6 +103,7 @@

    All Classes

  • ShiftGears
  • ShiftWithSensorComponent
  • ShooterSimple
  • +
  • SimpleButton
  • SimpleMotor
  • SimpleMotorCluster
  • SimpleUnidirectionalDrive
  • @@ -107,23 +114,25 @@

    All Classes

  • SpinUpShooter
  • SpinUpThenShoot
  • StartCompressor
  • +
  • SubsystemAHRS
  • SubsystemBinaryMotor
  • SubsystemConditional
  • SubsystemIntake
  • SubsystemIntake.IntakeMode
  • SubsystemMP
  • SubsystemMPTwoSides
  • -
  • SubsystemNavX
  • SubsystemShooter
  • SubsystemShooter.ShooterState
  • SubsystemSolenoid
  • SwitchToGear
  • SwitchToHighGear
  • SwitchToLowGear
  • -
  • Throttle
  • +
  • Throttle
  • +
  • ThrottleBasic
  • ThrottleDeadbanded
  • ThrottleExponential
  • ThrottlePolynomial
  • +
  • ThrottleSum
  • ToggleIntaking
  • ToggleMotor
  • ToggleOverrideAutoShift
  • @@ -139,6 +148,10 @@

    All Classes

  • TurnMotorOn
  • UnidirectionalNavXDefaultDrive
  • UnidirectionalNavXShiftingDefaultDrive
  • +
  • UnidirectionalPoseEstimator
  • +
  • Updatable
  • +
  • Updater
  • +
  • VoltageRamp
  • WaitForMillis
  • YamlCommand
  • YamlCommandGroupWrapper
  • diff --git a/docs/allclasses-noframe.html b/docs/allclasses-noframe.html index 86907d93..7887a1c2 100644 --- a/docs/allclasses-noframe.html +++ b/docs/allclasses-noframe.html @@ -2,9 +2,9 @@ - + All Classes (RoboRIO 1.0 API) - + @@ -25,6 +25,7 @@

    All Classes

  • CommandButton
  • CommandSequence
  • DetermineNominalVoltage
  • +
  • DetermineVelVsVoltage
  • dPadButton
  • DriveAtSpeed
  • DriveShiftable
  • @@ -34,8 +35,7 @@

    All Classes

  • DriveTalonClusterShiftable
  • DriveUnidirectional
  • DriveUnidirectionalSimple
  • -
  • FactoryButton
  • -
  • FactoryJoystickButton
  • +
  • EnableMotors
  • FieldOrientedUnidirectionalDriveCommand
  • FieldOrientedUnidirectionalDriveCommand.AngularSnapPoint
  • FieldOrientedUnidirectionalDriveCommandShifting
  • @@ -54,13 +54,16 @@

    All Classes

  • Logger
  • LoggingShooter
  • MappedAHRS
  • +
  • MappedButton
  • MappedDigitalInput
  • MappedDoubleSolenoid
  • MappedJoystick
  • +
  • MappedRunnable
  • MappedUsbCamera
  • MappedVictor
  • MotionProfileData
  • NavXDriveStraight
  • +
  • NavXRumbleComponent
  • NavXTurnToAngle
  • NavXTurnToAngleRelative
  • OI
  • @@ -83,13 +86,16 @@

    All Classes

  • Polynomial
  • PressureSensor
  • RackShooter
  • +
  • ResetPosition
  • ResetShooter
  • Robot
  • RobotMap2017
  • +
  • Rumbleable
  • RunLoadedProfile
  • RunMotorWhileConditonMet
  • RunProfile
  • RunProfileTwoSides
  • +
  • RunRunnables
  • SetIntakeMode
  • Shiftable
  • Shiftable.gear
  • @@ -97,6 +103,7 @@

    All Classes

  • ShiftGears
  • ShiftWithSensorComponent
  • ShooterSimple
  • +
  • SimpleButton
  • SimpleMotor
  • SimpleMotorCluster
  • SimpleUnidirectionalDrive
  • @@ -107,23 +114,25 @@

    All Classes

  • SpinUpShooter
  • SpinUpThenShoot
  • StartCompressor
  • +
  • SubsystemAHRS
  • SubsystemBinaryMotor
  • SubsystemConditional
  • SubsystemIntake
  • SubsystemIntake.IntakeMode
  • SubsystemMP
  • SubsystemMPTwoSides
  • -
  • SubsystemNavX
  • SubsystemShooter
  • SubsystemShooter.ShooterState
  • SubsystemSolenoid
  • SwitchToGear
  • SwitchToHighGear
  • SwitchToLowGear
  • -
  • Throttle
  • +
  • Throttle
  • +
  • ThrottleBasic
  • ThrottleDeadbanded
  • ThrottleExponential
  • ThrottlePolynomial
  • +
  • ThrottleSum
  • ToggleIntaking
  • ToggleMotor
  • ToggleOverrideAutoShift
  • @@ -139,6 +148,10 @@

    All Classes

  • TurnMotorOn
  • UnidirectionalNavXDefaultDrive
  • UnidirectionalNavXShiftingDefaultDrive
  • +
  • UnidirectionalPoseEstimator
  • +
  • Updatable
  • +
  • Updater
  • +
  • VoltageRamp
  • WaitForMillis
  • YamlCommand
  • YamlCommandGroupWrapper
  • diff --git a/docs/constant-values.html b/docs/constant-values.html index 015557fb..092be34d 100644 --- a/docs/constant-values.html +++ b/docs/constant-values.html @@ -2,9 +2,9 @@ - + Constant Field Values (RoboRIO 1.0 API) - + diff --git a/docs/deprecated-list.html b/docs/deprecated-list.html index 8b9c5239..c416d625 100644 --- a/docs/deprecated-list.html +++ b/docs/deprecated-list.html @@ -2,9 +2,9 @@ - + Deprecated List (RoboRIO 1.0 API) - + diff --git a/docs/help-doc.html b/docs/help-doc.html index a7f7db06..11e5d0bc 100644 --- a/docs/help-doc.html +++ b/docs/help-doc.html @@ -2,9 +2,9 @@ - + API Help (RoboRIO 1.0 API) - + diff --git a/docs/index-all.html b/docs/index-all.html index 61308252..29f39abc 100644 --- a/docs/index-all.html +++ b/docs/index-all.html @@ -2,9 +2,9 @@ - + Index (RoboRIO 1.0 API) - + @@ -73,6 +73,15 @@

    A

    +
    addAbsolutePos(double, double, long) - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Add an absolute position at the given time stamp.
    +
    +
    addAbsolutePos(double, double, long, double) - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Add an absolute position at the given time stamp, using an angle measured to verify that the absolute position is + correct.
    +
    addEvent(String, Class) - Static method in class org.usfirst.frc.team449.robot.other.Logger
    Log an event to be written to the event log file.
    @@ -165,6 +174,14 @@

    B

    C

    +
    cachedOutput - Variable in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    The cached value of the output.
    +
    +
    cachedValue - Variable in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    The cached output.
    +
    calcValues() - Method in class org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOrientedPosCos
    Calculate the theta and vel values, can be called multiple times per tic but will only execute logic once.
    @@ -209,7 +226,7 @@

    C

    A button mapped to a command.
    -
    CommandButton(FactoryButton, YamlCommand, CommandButton.Action) - Constructor for class org.usfirst.frc.team449.robot.oi.buttons.CommandButton
    +
    CommandButton(MappedButton, YamlCommand, CommandButton.Action) - Constructor for class org.usfirst.frc.team449.robot.oi.buttons.CommandButton
    Default constructor.
    @@ -229,6 +246,22 @@

    C

    Whether the driver is trying to drive straight.
    +
    commandingStraightCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    Whether the driver was trying to drive straight when values were cached.
    +
    +
    commandingStraightCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
    +
    +
    Whether the driver was trying to drive straight when values were cached.
    +
    +
    commandingStraightCached() - Method in interface org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional
    +
    +
    Whether the driver was trying to drive straight when values were cached.
    +
    +
    commandingStraightCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITankSimple
    +
    +
    Whether the driver was trying to drive straight when values were cached.
    +
    CommandSequence - Class in org.usfirst.frc.team449.robot.commands.general
    A command group that takes a list of commands and runs them in the order given.
    @@ -237,10 +270,6 @@

    C

    Default constructor
    -
    constructButton(MappedJoystick, Integer, Integer, Double, Integer) - Static method in class org.usfirst.frc.team449.robot.oi.buttons.FactoryButton
    -
    -
    Static factory for constructing different types of buttons.
    -
    currentGear - Variable in class org.usfirst.frc.team449.robot.components.ShiftComponent
    The gear this component is currently in.
    @@ -273,6 +302,14 @@

    D

    Default constructor
    +
    DetermineVelVsVoltage<T extends YamlSubsystem & DriveUnidirectional> - Class in org.usfirst.frc.team449.robot.drive.unidirectional.commands
    +
    +
    A command to run the robot at a range of voltages and record the velocity.
    +
    +
    DetermineVelVsVoltage(T, double, int, double[]) - Constructor for class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Default constructor.
    +
    disable() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    Disable the motors.
    @@ -297,6 +334,10 @@

    D

    Run when we disable.
    +
    disabledPeriodic() - Method in class org.usfirst.frc.team449.robot.Robot
    +
    +
    Run every tic while disabled
    +
    dPadButton - Class in org.usfirst.frc.team449.robot.oi.buttons
    A Button triggered by pushing the D-pad to a specific angle.
    @@ -379,6 +420,14 @@

    E

    Enables the motor, if applicable.
    +
    EnableMotors - Class in org.usfirst.frc.team449.robot.drive.commands
    +
    +
    Enables the motors of the given drive subsystem.
    +
    +
    EnableMotors(DriveSubsystem) - Constructor for class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Default constructor
    +
    enableMotors() - Method in interface org.usfirst.frc.team449.robot.drive.DriveSubsystem
    If this drive uses motors that can be disabled, enable them.
    @@ -399,6 +448,10 @@

    E

    Converts the velocity read by the talon's getVelocity() method to the FPS of the output shaft.
    +
    end() - Method in class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
    +
    Log on exit.
    +
    end() - Method in class org.usfirst.frc.team449.robot.commands.multiInterface.drive.FieldOrientedUnidirectionalDriveCommand
    Log when this command ends
    @@ -431,6 +484,14 @@

    E

    Stop the motor and log that the command has ended.
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Log when this command ends
    +
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Log when this command ends
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift
    Log when this command ends.
    @@ -443,10 +504,18 @@

    E

    Stop the drive and log when the command ends.
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Do nothing, no logging because we want to be able to use R's subset method to find the max speeds.
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed
    Stop the drive when the command ends.
    +
    end() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Log and stop on end.
    +
    end() - Method in class org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.ShiftGears
    Log when this command ends
    @@ -543,6 +612,10 @@

    E

    Log when this command ends
    +
    execute() - Method in class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
    +
    Run all the runnables in the order they were given.
    +
    execute() - Method in class org.usfirst.frc.team449.robot.commands.multiInterface.drive.FieldOrientedUnidirectionalDriveCommand
    Set PID setpoint to processed controller setpoint.
    @@ -563,6 +636,14 @@

    E

    Run the motor
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Do the state change.
    +
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Do the state change.
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift
    Override autoshifting.
    @@ -575,6 +656,10 @@

    E

    Send output to motors
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Update the max speed for this trial and check if this trial is finished.
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed
    Send output to motors and log data
    @@ -587,6 +672,10 @@

    E

    Give output to the motors based on the stick inputs.
    +
    execute() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Update the output based on how long it's been since execute() was last run.
    +
    execute() - Method in class org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.ShiftGears
    Switch gears
    @@ -685,25 +774,11 @@

    E

    F

    -
    FactoryButton - Class in org.usfirst.frc.team449.robot.oi.buttons
    -
    -
    A factory for constructing a button..
    -
    -
    FactoryButton() - Constructor for class org.usfirst.frc.team449.robot.oi.buttons.FactoryButton
    -
     
    -
    FactoryJoystickButton - Class in org.usfirst.frc.team449.robot.oi.buttons
    -
    -
    A version of JoystickButton that is a FactoryButton.
    -
    -
    FactoryJoystickButton(MappedJoystick, int) - Constructor for class org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton
    -
    -
    Default constructor.
    -
    feetToEncoder(double) - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    Convert a distance from feet to encoder reading in native units.
    -
    FieldOrientedUnidirectionalDriveCommand<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    FieldOrientedUnidirectionalDriveCommand<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Unidirectional drive with field-oriented control
    @@ -715,7 +790,7 @@

    F

    A data-holding class representing an angular setpoint to "snap" the controller output to.
    -
    FieldOrientedUnidirectionalDriveCommandShifting<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX & DriveShiftable> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    FieldOrientedUnidirectionalDriveCommandShifting<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS & DriveShiftable> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Unidirectional drive with field-oriented control and autoshifting.
    @@ -735,7 +810,7 @@

    F

    Component wrapper on the CTRE CANTalon, with unit conversions to/from FPS built in.
    -
    FPSTalon(int, boolean, boolean, Boolean, Boolean, Double, Double, Double, Double, Integer, double, CANTalon.FeedbackDevice, Integer, boolean, List<FPSTalon.PerGearSettings>, Shiftable.gear, Integer, Integer, Double, List<FPSTalon.SlaveTalon>) - Constructor for class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    +
    FPSTalon(int, boolean, boolean, boolean, Boolean, Boolean, Double, Double, Double, Double, Integer, double, CANTalon.FeedbackDevice, Integer, boolean, List<FPSTalon.PerGearSettings>, Shiftable.gear, Integer, Integer, Double, Map<CANTalon.StatusFrameRate, Integer>, Integer, List<FPSTalon.SlaveTalon>) - Constructor for class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    Default constructor.
    @@ -749,7 +824,8 @@

    F

    FPSToEncoder(double) - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    -
    Converts from the velocity of the output shaft to what the talon's getVelocity() method would read at that velocity.
    +
    Converts from the velocity of the output shaft to what the talon's getVelocity() method would read at that + velocity.
    fullStop() - Method in interface org.usfirst.frc.team449.robot.drive.DriveSubsystem
    @@ -773,7 +849,7 @@

    G

    Get whether this button is pressed
    -
    get() - Method in class org.usfirst.frc.team449.robot.oi.buttons.FactoryJoystickButton
    +
    get() - Method in class org.usfirst.frc.team449.robot.oi.buttons.SimpleButton
    Get whether the button is pressed.
    @@ -791,6 +867,38 @@

    G

    getAllianceSwitch() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    +
    getAngularDisplacement() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's angular displacement since being turned on.
    +
    +
    getAngularDisplacement() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's angular displacement since being turned on.
    +
    +
    getAngularDisplacementCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's cached angular displacement since being turned on.
    +
    +
    getAngularDisplacementCached() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's cached angular displacement since being turned on.
    +
    +
    getAngularVel() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's angular velocity.
    +
    +
    getAngularVel() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's angular velocity.
    +
    +
    getAngularVelCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's cached angular velocity.
    +
    +
    getAngularVelCached() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's cached angular velocity.
    +
    getAutoStartupCommand() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getBoilerAuto() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    @@ -835,8 +943,16 @@

    G

    Get the data this subsystem logs every loop.
    +
    getData() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad
    +
    +
    Get the data this subsystem logs every loop.
    +
    getData() - Method in class org.usfirst.frc.team449.robot.other.MotionProfileData
     
    +
    getData() - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Get the data this subsystem logs every loop.
    +
    getData() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited
    Get the data this subsystem logs every loop.
    @@ -863,6 +979,10 @@

    G

    getFeederAuto() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    +
    getFrictionCompFPSFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getFrictionCompFPSRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    getFwd() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    Get the velocity input.
    @@ -874,6 +994,10 @@

    G

    The output of the throttle controlling linear velocity, smoothed and adjusted according to what type of joystick it is.
    +
    getFwdCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    Get the cached velocity input.
    +
    getFwdNominalOutputVoltage() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    getFwdPeakOutputVoltage() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    @@ -888,19 +1012,19 @@

    G

     
    getGearHandler() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    -
    getGyroOutput() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    getHeader() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    -
    Get the robot's heading using the navX
    +
    Get the headers for the data this subsystem logs every loop.
    -
    getGyroOutput() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX
    +
    getHeader() - Method in interface org.usfirst.frc.team449.robot.generalInterfaces.loggable.Loggable
    -
    Get the robot's heading using the navX
    +
    Get the headers for the data this subsystem logs every loop.
    -
    getHeader() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    getHeader() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad
    Get the headers for the data this subsystem logs every loop.
    -
    getHeader() - Method in interface org.usfirst.frc.team449.robot.generalInterfaces.loggable.Loggable
    +
    getHeader() - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    Get the headers for the data this subsystem logs every loop.
    @@ -916,8 +1040,28 @@

    G

    Get the headers for the data this subsystem logs every loop.
    +
    getHeading() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's heading using the navX
    +
    +
    getHeading() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's heading.
    +
    +
    getHeadingCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the robot's cached heading.
    +
    +
    getHeadingCached() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
    +
    +
    Get the robot's cached heading.
    +
    getIntake() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    +
    getKaOverKvFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getKaOverKvRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    getkD() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    getkI() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    @@ -940,6 +1084,46 @@

    G

    The output to be given to the left side of the drive.
    +
    getLeftOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    The cached output to be given to the left side of the drive.
    +
    +
    getLeftOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
    +
    +
    The cached output to be given to the left side of the drive.
    +
    +
    getLeftOutputCached() - Method in interface org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional
    +
    +
    The cached output to be given to the left side of the drive.
    +
    +
    getLeftOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank
    +
    +
    The cached output to be given to the left side of the drive.
    +
    +
    getLeftPos() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the position of the left side of the drive.
    +
    +
    getLeftPos() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the position of the left side of the drive.
    +
    +
    getLeftPos() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the position of the left side of the drive.
    +
    +
    getLeftPosCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the cached position of the left side of the drive.
    +
    +
    getLeftPosCached() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the cached position of the left side of the drive.
    +
    +
    getLeftPosCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the cached position of the left side of the drive.
    +
    getLeftProfiles() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getLeftTestProfile() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    @@ -952,6 +1136,10 @@

    G

    Get the throttle for the left side of the drive.
    +
    getLeftThrottleCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank
    +
    +
    Get the cached throttle for the left side of the drive.
    +
    getLeftVel() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    Get the velocity of the left side of the drive.
    @@ -964,6 +1152,18 @@

    G

    Get the velocity of the left side of the drive.
    +
    getLeftVelCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the cached velocity of the left side of the drive.
    +
    +
    getLeftVelCached() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the cached velocity of the left side of the drive.
    +
    +
    getLeftVelCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the cached velocity of the left side of the drive.
    +
    getLocationDial() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getLogger() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    @@ -974,17 +1174,27 @@

    G

     
    getMaxSpeed() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    +
    getMaxSpeedMPFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getMaxSpeedMPRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    getMode() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.intake.IntakeFixedAndActuated
     
    getMode() - Method in class org.usfirst.frc.team449.robot.subsystem.interfaces.intake.IntakeSimple
     
    getMode() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.intake.SubsystemIntake
     
    -
    getMotionProfileD() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
    getMotionProfileDFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getMotionProfileDRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getMotionProfileIFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    -
    getMotionProfileI() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
    getMotionProfileIRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    -
    getMotionProfileP() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
    getMotionProfilePFwd() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
     
    +
    getMotionProfilePRev() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
     
    getName() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    @@ -994,6 +1204,14 @@

    G

    Get the name of this object.
    +
    getName() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcadeWithDPad
    +
    +
    Get the name of this object.
    +
    +
    getName() - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Get the name of this object.
    +
    getName() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited
    Get the name of this object.
    @@ -1006,10 +1224,6 @@

    G

    Get the name of this object.
    -
    getNavX() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    -
     
    -
    getNavX() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX
    -
     
    getNonMPAutoCommand() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getNumVal() - Method in enum org.usfirst.frc.team449.robot.generalInterfaces.shiftable.Shiftable.gear
    @@ -1028,14 +1242,22 @@

    G

     
    getOverrideAutoshift() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable
     
    -
    getOverrideNavX() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    getOverrideGyro() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
     
    -
    getOverrideNavX() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX
    +
    getOverrideGyro() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
     
    +
    getPIDSourceType() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    Get which parameter of the device you are using as a process control variable.
    +
    getPneumatics() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getPort() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.SlaveTalon
     
    +
    getPos() - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Get the current absolute position of the robot
    +
    getPositionFeet() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
     
    getPowerToCoefficientMap() - Method in class org.usfirst.frc.team449.robot.other.Polynomial
    @@ -1064,6 +1286,46 @@

    G

    The output to be given to the right side of the drive.
    +
    getRightOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    The cached output to be given to the right side of the drive.
    +
    +
    getRightOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
    +
    +
    The cached output to be given to the right side of the drive.
    +
    +
    getRightOutputCached() - Method in interface org.usfirst.frc.team449.robot.oi.unidirectional.OIUnidirectional
    +
    +
    The cached output to be given to the right side of the drive.
    +
    +
    getRightOutputCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank
    +
    +
    The cached output to be given to the right side of the drive.
    +
    +
    getRightPos() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the position of the right side of the drive.
    +
    +
    getRightPos() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the position of the right side of the drive.
    +
    +
    getRightPos() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the position of the right side of the drive.
    +
    +
    getRightPosCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the cached position of the right side of the drive.
    +
    +
    getRightPosCached() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the cached position of the right side of the drive.
    +
    +
    getRightPosCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the cached position of the right side of the drive.
    +
    getRightProfiles() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getRightTestProfile() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    @@ -1076,6 +1338,10 @@

    G

    Get the throttle for the right side of the drive.
    +
    getRightThrottleCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank
    +
    +
    Get the cached throttle for the right side of the drive.
    +
    getRightVel() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    Get the velocity of the right side of the drive.
    @@ -1088,6 +1354,18 @@

    G

    Get the velocity of the right side of the drive.
    +
    getRightVelCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Get the cached velocity of the right side of the drive.
    +
    +
    getRightVelCached() - Method in interface org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectional
    +
    +
    Get the cached velocity of the right side of the drive.
    +
    +
    getRightVelCached() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Get the cached velocity of the right side of the drive.
    +
    getRIOduinoPort() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
     
    getRot() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    @@ -1100,6 +1378,10 @@

    G

    Get the output of the D-pad or turning joystick, whichever is in use.
    +
    getRotCached() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    Get the cached rotational input.
    +
    getServer() - Method in class org.usfirst.frc.team449.robot.subsystem.singleImplementation.camera.CameraNetwork
     
    getSetpoint() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    @@ -1128,6 +1410,8 @@

    G

     
    getSpinUpTimeMillis() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.shooter.SubsystemShooter
     
    +
    getStartupCommand() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    +
     
    getStatus() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.MappedDigitalInput
    Get the status of each pin specified in the map, in the order they were specified.
    @@ -1144,9 +1428,15 @@

    G

    Get the absolute angle for the robot to move towards.
    +
    getUpdater() - Method in class org.usfirst.frc.team449.robot.RobotMap2017
    +
     
    getUpperBound() - Method in class org.usfirst.frc.team449.robot.commands.multiInterface.drive.FieldOrientedUnidirectionalDriveCommand.AngularSnapPoint
     
    -
    getValue() - Method in class org.usfirst.frc.team449.robot.oi.throttles.Throttle
    +
    getValue() - Method in interface org.usfirst.frc.team449.robot.oi.throttles.Throttle
    +
    +
    Get the output of the throttle this object represents.
    +
    +
    getValue() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    Gets the raw value from the stick and inverts it if necessary.
    @@ -1162,6 +1452,22 @@

    G

    Passes the deadbanded joystick output to the polynomial, while preserving sign.
    +
    getValue() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    Sums the throttles and returns their output
    +
    +
    getValueCached() - Method in interface org.usfirst.frc.team449.robot.oi.throttles.Throttle
    +
    +
    Get the cached output of the throttle this object represents.
    +
    +
    getValueCached() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    Get the cached output of the throttle this object represents.
    +
    +
    getValueCached() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    Get the cached output of the throttle this object represents.
    +
    getVel() - Method in interface org.usfirst.frc.team449.robot.oi.fieldoriented.OIFieldOriented
    Get the velocity for the robot to go at.
    @@ -1174,6 +1480,10 @@

    G

    Get the velocity of the CANTalon in FPS.
    +
    gsToFeetPerSecondSquared(double) - Static method in class org.usfirst.frc.team449.robot.jacksonWrappers.MappedAHRS
    +
    +
    Convert from gs (acceleration due to gravity) to feet/(second^2).
    +
    @@ -1243,6 +1553,10 @@

    I

    Do nothing.
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
    +
    Log on init
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.commands.general.WaitForMillis
    Store the start time.
    @@ -1271,6 +1585,14 @@

    I

    Log when this command is initialized
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Log when this command is initialized
    +
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Log when this command is initialized
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift
    Log on initialization
    @@ -1283,6 +1605,10 @@

    I

    Log initialization
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Reset the encoder position and variables.
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed
    Set up start time.
    @@ -1295,6 +1621,10 @@

    I

    Stop the drive for safety reasons.
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Reset the output
    +
    initialize() - Method in class org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.ShiftGears
    Log when this command is initialized
    @@ -1407,6 +1737,10 @@

    I

    Default constructor
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
    +
    Log when interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.commands.multiInterface.drive.FieldOrientedUnidirectionalDriveCommand
    Log when this command is interrupted.
    @@ -1439,6 +1773,14 @@

    I

    Stop the motor and log that the command has been interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Log when this command is interrupted.
    +
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Log when this command is interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift
    Log when interrupted
    @@ -1451,6 +1793,10 @@

    I

    Log and stop the drive when the command is interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Log when interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed
    Log and stop the drive when the command is interrupted.
    @@ -1463,6 +1809,10 @@

    I

    Log and brake when interrupted.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Log on interrupt.
    +
    interrupted() - Method in class org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.ShiftGears
    Log when this command is interrupted.
    @@ -1563,6 +1913,12 @@

    I

     
    isConditionTrue() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.conditional.SubsystemConditional
     
    +
    isConditionTrueCached() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited
    +
     
    +
    isConditionTrueCached() - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.conditional.SubsystemConditional
    +
     
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
     
    isFinished() - Method in class org.usfirst.frc.team449.robot.commands.general.WaitForMillis
    Finish if the specified amount of time has passed.
    @@ -1587,6 +1943,14 @@

    I

    Stop when the condition is met.
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.commands.EnableMotors
    +
    +
    Finish immediately because this is a state-change command.
    +
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Finish immediately because this is a state-change command.
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.shifting.commands.OverrideAutoShift
    Finish immediately because this is a state-change command.
    @@ -1599,6 +1963,10 @@

    I

    Exit if the motors are moving.
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DetermineVelVsVoltage
    +
    +
    Finish when all trials have been run.
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.DriveAtSpeed
    Exit after the command's been running for long enough
    @@ -1611,6 +1979,10 @@

    I

    Run constantly because this is a default drive
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Exit if the output is greater than the motors can produce.
    +
    isFinished() - Method in class org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands.ShiftGears
    Finish immediately because this is a state-change command.
    @@ -1705,6 +2077,8 @@

    I

    isInverted() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.SlaveTalon
     
    +
    isInverted() - Method in class org.usfirst.frc.team449.robot.other.MotionProfileData
    +
     
    isMotorOn() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited
     
    isMotorOn() - Method in class org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor.BinaryMotorSimple
    @@ -1719,7 +2093,7 @@

    I

    J

    -
    JiggleRobot<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    JiggleRobot<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Rotates the robot back and forth in order to dislodge any stuck balls.
    @@ -1823,6 +2197,12 @@

    M

    Default constructor.
    +
    MappedButton - Class in org.usfirst.frc.team449.robot.jacksonWrappers
    +
    +
    A jackson-compatible wrapper on WPILib's Button.
    +
    +
    MappedButton() - Constructor for class org.usfirst.frc.team449.robot.jacksonWrappers.MappedButton
    +
     
    MappedDigitalInput - Class in org.usfirst.frc.team449.robot.jacksonWrappers
    A series of roboRIO digital input pins.
    @@ -1847,6 +2227,10 @@

    M

    Default constructor
    +
    MappedRunnable - Interface in org.usfirst.frc.team449.robot.jacksonWrappers
    +
    +
    A jackson-compatible wrapper on Java's Runnable.
    +
    MappedUsbCamera - Class in org.usfirst.frc.team449.robot.jacksonWrappers
    A Jackson-compatible wrapper on the UsbCamera.
    @@ -1881,7 +2265,7 @@

    M

    N

    -
    NavXDriveStraight<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    NavXDriveStraight<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Drives straight using the NavX gyro to keep a constant alignment.
    @@ -1889,7 +2273,15 @@

    N

    Default constructor.
    -
    NavXTurnToAngle<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    NavXRumbleComponent - Class in org.usfirst.frc.team449.robot.components
    +
    +
    A component to rumble controllers based off the jerk measurements from a NavX.
    +
    +
    NavXRumbleComponent(MappedAHRS, List<Rumbleable>, double, double, boolean, boolean) - Constructor for class org.usfirst.frc.team449.robot.components.NavXRumbleComponent
    +
    +
    Default constructor.
    +
    +
    NavXTurnToAngle<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Turns to a specified angle, relative to the angle the navX was at when the robot was turned on.
    @@ -1897,7 +2289,7 @@

    N

    Default constructor.
    -
    NavXTurnToAngleRelative<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    NavXTurnToAngleRelative<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Turn a certain number of degrees from the current heading.
    @@ -1961,7 +2353,7 @@

    O

    OIOutreach - Class in org.usfirst.frc.team449.robot.oi.unidirectional
     
    -
    OIOutreach(OIUnidirectional, OIUnidirectional, FactoryButton) - Constructor for class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
    +
    OIOutreach(OIUnidirectional, OIUnidirectional, MappedButton) - Constructor for class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
     
    OITank - Class in org.usfirst.frc.team449.robot.oi.unidirectional.tank
    @@ -1997,6 +2389,8 @@

    O

     
    org.usfirst.frc.team449.robot.drive - package org.usfirst.frc.team449.robot.drive
     
    +
    org.usfirst.frc.team449.robot.drive.commands - package org.usfirst.frc.team449.robot.drive.commands
    +
     
    org.usfirst.frc.team449.robot.drive.shifting - package org.usfirst.frc.team449.robot.drive.shifting
     
    org.usfirst.frc.team449.robot.drive.shifting.commands - package org.usfirst.frc.team449.robot.drive.shifting.commands
    @@ -2007,12 +2401,16 @@

    O

     
    org.usfirst.frc.team449.robot.generalInterfaces.loggable - package org.usfirst.frc.team449.robot.generalInterfaces.loggable
     
    +
    org.usfirst.frc.team449.robot.generalInterfaces.rumbleable - package org.usfirst.frc.team449.robot.generalInterfaces.rumbleable
    +
     
    org.usfirst.frc.team449.robot.generalInterfaces.shiftable - package org.usfirst.frc.team449.robot.generalInterfaces.shiftable
     
    org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands - package org.usfirst.frc.team449.robot.generalInterfaces.shiftable.commands
     
    org.usfirst.frc.team449.robot.generalInterfaces.simpleMotor - package org.usfirst.frc.team449.robot.generalInterfaces.simpleMotor
     
    +
    org.usfirst.frc.team449.robot.generalInterfaces.updatable - package org.usfirst.frc.team449.robot.generalInterfaces.updatable
    +
     
    org.usfirst.frc.team449.robot.jacksonWrappers - package org.usfirst.frc.team449.robot.jacksonWrappers
     
    org.usfirst.frc.team449.robot.oi - package org.usfirst.frc.team449.robot.oi
    @@ -2091,7 +2489,7 @@

    O

    Set whether or not to override the navX.
    -
    OverrideNavX(SubsystemNavX, boolean) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX
    +
    OverrideNavX(SubsystemAHRS, boolean) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.OverrideNavX
    Default constructor.
    @@ -2109,7 +2507,7 @@

    P

    Default constructor
    -
    PerGearSettings(int, Shiftable.gear, Double, Double, Double, Double, Double, Double, double, double, double, double, double, double) - Constructor for class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    +
    PerGearSettings(int, Shiftable.gear, Double, Double, Double, Double, Double, Double, double, double, double, double, double, double, Double, Double, Double, Double, Double, Double, double, Double, Double) - Constructor for class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon.PerGearSettings
    Default constructor.
    @@ -2121,7 +2519,7 @@

    P

    A command that uses a navX to turn to a certain angle.
    -
    PIDAngleCommand(double, int, double, Double, double, boolean, SubsystemNavX, double, double, double) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand
    +
    PIDAngleCommand(double, int, double, Double, double, boolean, SubsystemAHRS, double, double, double) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.PIDAngleCommand
    Default constructor.
    @@ -2133,6 +2531,10 @@

    P

    Instantiate the CommandGroup
    +
    pidGet() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    Get the result to use in PIDController.
    +
    PIDTest<T extends YamlSubsystem & DriveUnidirectional> - Class in org.usfirst.frc.team449.robot.drive.unidirectional.commands
    Drive forward at constant speed then stop to tune PID.
    @@ -2207,9 +2609,25 @@

    R

    Get whether the subsystem is ready to run the loaded profile.
    +
    ResetPosition - Class in org.usfirst.frc.team449.robot.drive.commands
    +
    +
    Resets the positions of the motors of the given drive subsystem.
    +
    +
    ResetPosition(DriveSubsystem) - Constructor for class org.usfirst.frc.team449.robot.drive.commands.ResetPosition
    +
    +
    Default constructor
    +
    +
    resetPosition() - Method in interface org.usfirst.frc.team449.robot.drive.DriveSubsystem
    +
    +
    Reset the position of the drive if it has encoders.
    +
    resetPosition() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    -
    Reset the motor positions.
    +
    Reset the position of the drive if it has encoders.
    +
    +
    resetPosition() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Reset the position of the drive if it has encoders.
    resetPosition() - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    @@ -2249,14 +2667,38 @@

    R

    The Jackson-compatible object representing the entire robot.
    -
    RobotMap2017(List<CommandButton>, OI, Logger, DriveTalonCluster, YamlCommand, ClimberCurrentLimited, LoggingShooter, CameraNetwork, IntakeFixedAndActuated, Pneumatics, SolenoidSimple, Integer, MappedDigitalInput, MappedDigitalInput, MappedDigitalInput, YamlCommand, YamlCommand, YamlCommand, MotionProfileData, MotionProfileData, Map<String, MotionProfileData>, Map<String, MotionProfileData>, YamlCommand, YamlCommand, YamlCommand, boolean, Boolean) - Constructor for class org.usfirst.frc.team449.robot.RobotMap2017
    +
    RobotMap2017(List<CommandButton>, OI, Logger, DriveTalonCluster, YamlCommand, MappedRunnable, ClimberCurrentLimited, LoggingShooter, CameraNetwork, IntakeFixedAndActuated, Pneumatics, SolenoidSimple, Integer, MappedDigitalInput, MappedDigitalInput, MappedDigitalInput, YamlCommand, YamlCommand, YamlCommand, MotionProfileData, MotionProfileData, Map<String, MotionProfileData>, Map<String, MotionProfileData>, YamlCommand, YamlCommand, YamlCommand, YamlCommand, boolean, Boolean) - Constructor for class org.usfirst.frc.team449.robot.RobotMap2017
    Default constructor.
    +
    rumble(double, double) - Method in interface org.usfirst.frc.team449.robot.generalInterfaces.rumbleable.Rumbleable
    +
    +
    Rumble at a given strength on each side of the device.
    +
    +
    rumble(double, double) - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.MappedJoystick
    +
    +
    Rumble at a given strength on each side of the device.
    +
    +
    Rumbleable - Interface in org.usfirst.frc.team449.robot.generalInterfaces.rumbleable
    +
    +
    An interface for any sort of OI device that can rumble to give feedback to the driver.
    +
    +
    run() - Method in class org.usfirst.frc.team449.robot.components.NavXRumbleComponent
    +
    +
    Read the NavX jerk data and rumble the joysticks based off of it.
    +
    run() - Method in class org.usfirst.frc.team449.robot.other.Logger
    Print out all logged events to the event log and write all the telemetry data to the telemetry log.
    +
    run() - Method in class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Use the current gyro and encoder data to calculate how the robot has moved since the last time run was called.
    +
    +
    run() - Method in class org.usfirst.frc.team449.robot.other.Updater
    +
    +
    Update all the updatables.
    +
    RunLoadedProfile<T extends YamlSubsystem & SubsystemMP> - Class in org.usfirst.frc.team449.robot.subsystem.interfaces.motionProfile.commands
    Runs the command that is currently loaded in the given subsystem.
    @@ -2289,6 +2731,14 @@

    R

    Default constructor.
    +
    RunRunnables - Class in org.usfirst.frc.team449.robot.commands.general
    +
    +
    A command that runs any number of Runnable objects every tic.
    +
    +
    RunRunnables(MappedRunnable[]) - Constructor for class org.usfirst.frc.team449.robot.commands.general.RunRunnables
    +
    +
    Default constructor
    +
    @@ -2359,14 +2809,18 @@

    S

     
    setOverrideAutoshift(boolean) - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonClusterShiftable
     
    -
    setOverrideNavX(boolean) - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    setOverrideGyro(boolean) - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
     
    -
    setOverrideNavX(boolean) - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemNavX
    +
    setOverrideGyro(boolean) - Method in interface org.usfirst.frc.team449.robot.subsystem.interfaces.navX.SubsystemAHRS
     
    setPercentVoltage(double) - Method in class org.usfirst.frc.team449.robot.jacksonWrappers.FPSTalon
    Set the motor output voltage to a given percent of available voltage.
    +
    setPIDSourceType(PIDSourceType) - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    Set which parameter of the device you are using as a process control variable.
    +
    setpoint - Variable in class org.usfirst.frc.team449.robot.commands.multiInterface.drive.NavXTurnToAngle
    The angle to turn to.
    @@ -2457,6 +2911,14 @@

    S

    Default constructor
    +
    SimpleButton - Class in org.usfirst.frc.team449.robot.oi.buttons
    +
    +
    A version of JoystickButton that is a MappedButton.
    +
    +
    SimpleButton(MappedJoystick, int) - Constructor for class org.usfirst.frc.team449.robot.oi.buttons.SimpleButton
    +
    +
    Default constructor.
    +
    SimpleMotor - Interface in org.usfirst.frc.team449.robot.generalInterfaces.simpleMotor
     
    SimpleMotorCluster - Class in org.usfirst.frc.team449.robot.jacksonWrappers
    @@ -2555,7 +3017,7 @@

    S

    The time this command was initiated
    -
    stick - Variable in class org.usfirst.frc.team449.robot.oi.throttles.Throttle
    +
    stick - Variable in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    The stick we're using
    @@ -2603,6 +3065,10 @@

    S

    The subsystem to execute this command on.
    +
    SubsystemAHRS - Interface in org.usfirst.frc.team449.robot.subsystem.interfaces.navX
    +
    +
    A subsystem that has a navX on it.
    +
    SubsystemBinaryMotor - Interface in org.usfirst.frc.team449.robot.subsystem.interfaces.binaryMotor
    A subsystem with a motor that only needs to be run at one speed, e.g.
    @@ -2627,10 +3093,6 @@

    S

    An MP subsystem with two sides that therefore needs two profiles at a time.
    -
    SubsystemNavX - Interface in org.usfirst.frc.team449.robot.subsystem.interfaces.navX
    -
    -
    A subsystem that has a navX on it.
    -
    SubsystemShooter - Interface in org.usfirst.frc.team449.robot.subsystem.interfaces.shooter
    A subsystem with a shooter and feeder.
    @@ -2681,19 +3143,27 @@

    T

    Run every tick in teleop.
    -
    Throttle - Class in org.usfirst.frc.team449.robot.oi.throttles
    +
    testInit() - Method in class org.usfirst.frc.team449.robot.Robot
    +
    +
    Run when we first enable in test mode.
    +
    +
    Throttle - Interface in org.usfirst.frc.team449.robot.oi.throttles
    +
    +
    An object representing an axis of a stick on a joystick.
    +
    +
    ThrottleBasic - Class in org.usfirst.frc.team449.robot.oi.throttles
    A class representing a single axis on a joystick.
    -
    Throttle(MappedJoystick, int, boolean) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.Throttle
    +
    ThrottleBasic(MappedJoystick, int, boolean) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    -
    A basic constructor.
    +
    Default constructor.
    ThrottleDeadbanded - Class in org.usfirst.frc.team449.robot.oi.throttles
    -
    A throttle with a deadband.
    +
    A throttle with a deadband and smoothing.
    -
    ThrottleDeadbanded(MappedJoystick, int, double, boolean) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded
    +
    ThrottleDeadbanded(MappedJoystick, int, double, Double, boolean) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleDeadbanded
    A basic constructor.
    @@ -2701,7 +3171,7 @@

    T

    An exponentially-scaled throttle.
    -
    ThrottleExponential(MappedJoystick, int, double, boolean, double) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleExponential
    +
    ThrottleExponential(MappedJoystick, int, double, Double, boolean, double) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleExponential
    A basic constructor.
    @@ -2709,10 +3179,22 @@

    T

    A polynomially scaled throttle.
    -
    ThrottlePolynomial(MappedJoystick, int, double, boolean, Polynomial) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial
    +
    ThrottlePolynomial(MappedJoystick, int, double, Double, boolean, Polynomial) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottlePolynomial
    A basic constructor.
    +
    throttles - Variable in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    The throttles to sum.
    +
    +
    ThrottleSum - Class in org.usfirst.frc.team449.robot.oi.throttles
    +
    +
    A Throttle that sums any number of other Throttles.
    +
    +
    ThrottleSum(Throttle[]) - Constructor for class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    Default constructor.
    +
    ToggleIntaking - Class in org.usfirst.frc.team449.robot.subsystem.interfaces.intake.commands
    Toggles whether the subsystem is off or set to a given mode.
    @@ -2741,7 +3223,7 @@

    T

    Toggle whether or not to override the navX.
    -
    ToggleOverrideNavX(SubsystemNavX) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.ToggleOverrideNavX
    +
    ToggleOverrideNavX(SubsystemAHRS) - Constructor for class org.usfirst.frc.team449.robot.subsystem.interfaces.navX.commands.ToggleOverrideNavX
    Default constructor.
    @@ -2901,7 +3383,7 @@

    T

    U

    -
    UnidirectionalNavXDefaultDrive<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    UnidirectionalNavXDefaultDrive<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Drive with arcade drive setup, and when the driver isn't turning, use a NavX to stabilize the robot's alignment.
    @@ -2909,7 +3391,7 @@

    U

    Default constructor
    -
    UnidirectionalNavXShiftingDefaultDrive<T extends YamlSubsystem & DriveUnidirectional & SubsystemNavX & DriveShiftable> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    +
    UnidirectionalNavXShiftingDefaultDrive<T extends YamlSubsystem & DriveUnidirectional & SubsystemAHRS & DriveShiftable> - Class in org.usfirst.frc.team449.robot.commands.multiInterface.drive
    Drive with arcade drive setup, autoshift, and when the driver isn't turning, use a NavX to stabilize the robot's alignment.
    @@ -2918,6 +3400,64 @@

    U

    Default constructor
    +
    UnidirectionalPoseEstimator<T extends SubsystemAHRS & DriveUnidirectional> - Class in org.usfirst.frc.team449.robot.other
    +
    +
    A Runnable for pose estimation that can take absolute positions.
    +
    +
    UnidirectionalPoseEstimator(Double, T, double, double, double, double) - Constructor for class org.usfirst.frc.team449.robot.other.UnidirectionalPoseEstimator
    +
    +
    Default constructor.
    +
    +
    Updatable - Interface in org.usfirst.frc.team449.robot.generalInterfaces.updatable
    +
    +
    An interface for any object that caches values.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveTalonCluster
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.drive.unidirectional.DriveUnidirectionalSimple
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in interface org.usfirst.frc.team449.robot.generalInterfaces.updatable.Updatable
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleBasic
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.throttles.ThrottleSum
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.arcade.OIArcade
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.OIOutreach
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITank
    +
    +
    Updates all cached values with current ones.
    +
    +
    update() - Method in class org.usfirst.frc.team449.robot.oi.unidirectional.tank.OITankSimple
    +
     
    +
    update() - Method in class org.usfirst.frc.team449.robot.subsystem.complex.climber.ClimberCurrentLimited
    +
    +
    Updates all cached values with current ones.
    +
    +
    Updater - Class in org.usfirst.frc.team449.robot.other
    +
    +
    A Runnable for updating cached variables.
    +
    +
    Updater(Updatable[]) - Constructor for class org.usfirst.frc.team449.robot.other.Updater
    +
    +
    Default constructor
    +
    updateTime() - Static method in class org.usfirst.frc.team449.robot.other.Clock
    Updates the current time.
    @@ -2983,6 +3523,14 @@

    V

    Joystick scaling constant.
    +
    VoltageRamp - Class in org.usfirst.frc.team449.robot.drive.unidirectional.commands
    +
    +
    A command to ramp up the motors to full power at a given voltage rate.
    +
    +
    VoltageRamp(DriveUnidirectional, double) - Constructor for class org.usfirst.frc.team449.robot.drive.unidirectional.commands.VoltageRamp
    +
    +
    Default constructor
    +
    diff --git a/docs/index.html b/docs/index.html index 8f051be2..70e31097 100644 --- a/docs/index.html +++ b/docs/index.html @@ -2,7 +2,7 @@ - + RoboRIO 1.0 API @@ -18,7 +18,7 @@ catch(err) { } //--> -var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10}; +var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10}; var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]}; var altColor = "altColor"; var rowColor = "rowColor"; @@ -204,29 +204,41 @@

    Method Summary

    void +
    disabledPeriodic() +
    Run every tic while disabled
    + + + +void robotInit()
    The method that runs when the robot is turned on.
    - + void teleopInit()
    Run when we first enable in teleop.
    - + void teleopPeriodic()
    Run every tick in teleop.
    + +void +testInit() +
    Run when we first enable in test mode.
    + +
    • Methods inherited from class edu.wpi.first.wpilibj.IterativeRobot

      -disabledPeriodic, robotPeriodic, startCompetition, testInit, testPeriodic
    • +robotPeriodic, startCompetition, testPeriodic
    • @@ -369,7 +381,7 @@

      autonomousPeriodic

      -
        +
        • disabledInit

          public void disabledInit()
          @@ -380,6 +392,34 @@

          disabledInit

        + + + +
          +
        • +

          testInit

          +
          public void testInit()
          +
          Run when we first enable in test mode.
          +
          +
          Overrides:
          +
          testInit in class edu.wpi.first.wpilibj.IterativeRobot
          +
          +
        • +
        + + + +
          +
        • +

          disabledPeriodic

          +
          public void disabledPeriodic()
          +
          Run every tic while disabled
          +
          +
          Overrides:
          +
          disabledPeriodic in class edu.wpi.first.wpilibj.IterativeRobot
          +
          +
        • +
    • diff --git a/docs/org/usfirst/frc/team449/robot/RobotMap2017.html b/docs/org/usfirst/frc/team449/robot/RobotMap2017.html index 0ea08157..6212c484 100644 --- a/docs/org/usfirst/frc/team449/robot/RobotMap2017.html +++ b/docs/org/usfirst/frc/team449/robot/RobotMap2017.html @@ -2,9 +2,9 @@ - + RobotMap2017 (RoboRIO 1.0 API) - + @@ -18,7 +18,7 @@ catch(err) { } //--> -var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10,"i8":10,"i9":10,"i10":10,"i11":10,"i12":10,"i13":10,"i14":10,"i15":10,"i16":10,"i17":10,"i18":10,"i19":10,"i20":10,"i21":10,"i22":10,"i23":10,"i24":10,"i25":10,"i26":10}; +var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10,"i8":10,"i9":10,"i10":10,"i11":10,"i12":10,"i13":10,"i14":10,"i15":10,"i16":10,"i17":10,"i18":10,"i19":10,"i20":10,"i21":10,"i22":10,"i23":10,"i24":10,"i25":10,"i26":10,"i27":10,"i28":10}; var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]}; var altColor = "altColor"; var rowColor = "rowColor"; @@ -129,11 +129,12 @@

      Constructor Summary

      Constructor and Description -RobotMap2017(java.util.List<CommandButton> buttons, +RobotMap2017(java.util.List<CommandButton> buttons, OI oi, Logger logger, DriveTalonCluster drive, YamlCommand defaultDriveCommand, + MappedRunnable updater, ClimberCurrentLimited climber, LoggingShooter shooter, CameraNetwork camera, @@ -154,6 +155,7 @@

      Constructor Summary

      YamlCommand nonMPAutoCommand, YamlCommand autoStartupCommand, YamlCommand teleopStartupCommand, + YamlCommand startupCommand, boolean testMP, java.lang.Boolean doMP)
      Default constructor.
      @@ -276,12 +278,20 @@

      Method Summary

      edu.wpi.first.wpilibj.command.Command -getTeleopStartupCommand()  +getStartupCommand()  +edu.wpi.first.wpilibj.command.Command +getTeleopStartupCommand()  + + boolean getTestMP()  + +java.lang.Runnable +getUpdater()  +
      • @@ -304,13 +314,13 @@

        Methods inherited from class java.lang.Object

        Constructor Detail

        - +
        • RobotMap2017

          -
          public RobotMap2017(@NotNull
          +
          public RobotMap2017(@Nullable
                               java.util.List<CommandButton> buttons,
                               @NotNull
                               OI oi,
          @@ -320,6 +330,8 @@ 

          RobotMap2017

          DriveTalonCluster drive, @NotNull YamlCommand defaultDriveCommand, + @NotNull + MappedRunnable updater, @Nullable ClimberCurrentLimited climber, @Nullable @@ -360,17 +372,20 @@

          RobotMap2017

          YamlCommand autoStartupCommand, @Nullable YamlCommand teleopStartupCommand, + @Nullable + YamlCommand startupCommand, boolean testMP, @Nullable java.lang.Boolean doMP)
          Default constructor.
          Parameters:
          -
          buttons - The buttons for controlling this robot.
          +
          buttons - The buttons for controlling this robot. Can be null for an empty list.
          oi - The OI for controlling this robot's drive.
          logger - The logger for recording events and telemetry data.
          drive - The drive.
          defaultDriveCommand - The command for the drive to run during the teleoperated period.
          +
          updater - A runnable that updates cached variables.
          climber - The climber for boarding the airship. Can be null.
          shooter - The multiSubsystem for shooting fuel. Can be null.
          camera - The cameras on this robot. Can be null.
          @@ -379,31 +394,32 @@

          RobotMap2017

          gearHandler - The gear handler on this robot. Can be null.
          RIOduinoPort - The I2C port of the RIOduino plugged into this robot. Can be null.
          allianceSwitch - The switch for selecting which alliance we're on. Can be null if doMP is false or - testMP is true, but otherwise must have a value.
          + testMP is true, but otherwise must have a value.
          dropGearSwitch - The switch for deciding whether or not to drop the gear. Can be null if doMP is false - or testMP is true, but otherwise must have a value.
          -
          locationDial - The dial for selecting which side of the field the robot is on. Can be null if doMP is - false or testMP is true, but otherwise must have a value.
          + or testMP is true, but otherwise must have a value. +
          locationDial - The dial for selecting which side of the field the robot is on. Can be null if doMP + is false or testMP is true, but otherwise must have a value.
          boilerAuto - The command to run in autonomous on the boiler side of the field. Can be null if doMP - is false or testMP is true, but otherwise must have a value.
          + is false or testMP is true, but otherwise must have a value.
          centerAuto - The command to run in autonomous on the center of the field. Can be null if doMP is - false or testMP is true, but otherwise must have a value.
          -
          feederAuto - The command to run in autonomous on the feeding station side of the field. Can be null - if doMP is false or testMP is true, but otherwise must have a value.
          + false or testMP is true, but otherwise must have a value. +
          feederAuto - The command to run in autonomous on the feeding station side of the field. Can be + null if doMP is false or testMP is true, but otherwise must have a value.
          leftTestProfile - The profile for the left side of the drive to run in test mode. Can be null if either - testMP or doMP are false, but otherwise must have a value.
          -
          rightTestProfile - The profile for the right side of the drive to run in test mode. Can be null if either - testMP or doMP are false, but otherwise must have a value.
          + testMP or doMP are false, but otherwise must have a value. +
          rightTestProfile - The profile for the right side of the drive to run in test mode. Can be null if + either testMP or doMP are false, but otherwise must have a value.
          leftProfiles - The starting position to peg profiles for the left side. Should have options for - "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". - Can be null if doMP is false or testMP is true, but otherwise must have a value.
          + "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + Can be null if doMP is false or testMP is true, but otherwise must have a value.
          rightProfiles - The starting position to peg profiles for the right side. Should have options for - "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". - Can be null if doMP is false or testMP is true, but otherwise must have a value.
          + "red_right", "red_center", "red_left", "blue_right", "blue_center", and "blue_left". + Can be null if doMP is false or testMP is true, but otherwise must have a value.
          nonMPAutoCommand - The command to run during autonomous if doMP is false. Can be null, and if it is, no - command is run during autonomous.
          + command is run during autonomous.
          autoStartupCommand - The command to be run when first enabled in autonomous mode.
          teleopStartupCommand - The command to be run when first enabled in teleoperated mode.
          +
          startupCommand - The command to be run when first enabled.
          testMP - Whether to run the test or real motion profile during autonomous. Defaults to false.
          doMP - Whether to run a motion profile during autonomous. Defaults to true.
          @@ -795,7 +811,7 @@

          getTeleopStartupCommand

          -
            +
            • getDoMP

              public boolean getDoMP()
              @@ -805,6 +821,34 @@

              getDoMP

            + + + +
              +
            • +

              getStartupCommand

              +
              @Nullable
              +public edu.wpi.first.wpilibj.command.Command getStartupCommand()
              +
              +
              Returns:
              +
              The command to be run when first enabled.
              +
              +
            • +
            + + + +
              +
            • +

              getUpdater

              +
              @NotNull
              +public java.lang.Runnable getUpdater()
              +
              +
              Returns:
              +
              A runnable that updates cached variables.
              +
              +
            • +
        • diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Boiler.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Boiler.html index 001f6f47..cd3301d9 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Boiler.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Boiler.html @@ -2,9 +2,9 @@ - + Auto2017Boiler (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Center.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Center.html index da653b55..bf52254a 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Center.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Center.html @@ -2,9 +2,9 @@ - + Auto2017Center (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Feeder.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Feeder.html index 498d3446..cd4aa356 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Feeder.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/Auto2017Feeder.html @@ -2,9 +2,9 @@ - + Auto2017Feeder (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-frame.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-frame.html index a6066f4e..8b6dd948 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-frame.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-frame.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team449.robot.commands.autonomous (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-summary.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-summary.html index 32020b59..2ecddb7f 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-summary.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-summary.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team449.robot.commands.autonomous (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-tree.html b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-tree.html index 18132ccb..212324e4 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-tree.html +++ b/docs/org/usfirst/frc/team449/robot/commands/autonomous/package-tree.html @@ -2,9 +2,9 @@ - + org.usfirst.frc.team449.robot.commands.autonomous Class Hierarchy (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/general/CommandSequence.html b/docs/org/usfirst/frc/team449/robot/commands/general/CommandSequence.html index 42e517a3..fa7350cb 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/general/CommandSequence.html +++ b/docs/org/usfirst/frc/team449/robot/commands/general/CommandSequence.html @@ -2,9 +2,9 @@ - + CommandSequence (RoboRIO 1.0 API) - + diff --git a/docs/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.html b/docs/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.html index b4c90c45..a78759ff 100644 --- a/docs/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.html +++ b/docs/org/usfirst/frc/team449/robot/commands/general/ParallelCommandGroup.html @@ -2,9 +2,9 @@ - + ParallelCommandGroup (RoboRIO 1.0 API) - + @@ -43,7 +43,7 @@
        @@ -198,14 +241,14 @@

        getLeftVel

        Get the velocity of the left side of the drive.
        Returns:
        -
        The signed velocity in rotations per second, or null if the drive doesn't have encoders.
        +
        The signed velocity in feet per second, or null if the drive doesn't have encoders.
      -
        +
        • getRightVel

          @Nullable
          @@ -213,7 +256,97 @@ 

          getRightVel

          Get the velocity of the right side of the drive.
          Returns:
          -
          The signed velocity in rotations per second, or null if the drive doesn't have encoders.
          +
          The signed velocity in feet per second, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getLeftPos

          +
          @Nullable
          +java.lang.Double getLeftPos()
          +
          Get the position of the left side of the drive.
          +
          +
          Returns:
          +
          The signed position in feet, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getRightPos

          +
          @Nullable
          +java.lang.Double getRightPos()
          +
          Get the position of the right side of the drive.
          +
          +
          Returns:
          +
          The signed position in feet, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getLeftVelCached

          +
          @Nullable
          +java.lang.Double getLeftVelCached()
          +
          Get the cached velocity of the left side of the drive.
          +
          +
          Returns:
          +
          The signed velocity in feet per second, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getRightVelCached

          +
          @Nullable
          +java.lang.Double getRightVelCached()
          +
          Get the cached velocity of the right side of the drive.
          +
          +
          Returns:
          +
          The signed velocity in feet per second, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getLeftPosCached

          +
          @Nullable
          +java.lang.Double getLeftPosCached()
          +
          Get the cached position of the left side of the drive.
          +
          +
          Returns:
          +
          The signed position in feet, or null if the drive doesn't have encoders.
          +
          +
        • +
        + + + +
          +
        • +

          getRightPosCached

          +
          @Nullable
          +java.lang.Double getRightPosCached()
          +
          Get the cached position of the right side of the drive.
          +
          +
          Returns:
          +
          The signed position in feet, or null if the drive doesn't have encoders.
        diff --git a/docs/org/usfirst/frc/team449/robot/drive/unidirectional/DriveUnidirectionalSimple.html b/docs/org/usfirst/frc/team449/robot/drive/unidirectional/DriveUnidirectionalSimple.html index b50464b6..95e3e876 100644 --- a/docs/org/usfirst/frc/team449/robot/drive/unidirectional/DriveUnidirectionalSimple.html +++ b/docs/org/usfirst/frc/team449/robot/drive/unidirectional/DriveUnidirectionalSimple.html @@ -2,9 +2,9 @@ - + DriveUnidirectionalSimple (RoboRIO 1.0 API) - + @@ -18,7 +18,7 @@ catch(err) { } //--> -var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10}; +var methods = {"i0":10,"i1":10,"i2":10,"i3":10,"i4":10,"i5":10,"i6":10,"i7":10,"i8":10,"i9":10,"i10":10,"i11":10,"i12":10,"i13":10}; var tabs = {65535:["t0","All Methods"],2:["t2","Instance Methods"],8:["t4","Concrete Methods"]}; var altColor = "altColor"; var rowColor = "rowColor"; @@ -118,7 +118,7 @@

        Class DriveUnidirectio
      • All Implemented Interfaces:
        -
        edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable, DriveSubsystem, DriveUnidirectional
        +
        edu.wpi.first.wpilibj.NamedSendable, edu.wpi.first.wpilibj.Sendable, DriveSubsystem, DriveUnidirectional, Updatable


        @@ -178,29 +178,77 @@

        Method Summary

        java.lang.Double +getLeftPos() +
        Get the position of the left side of the drive.
        + + + +java.lang.Double +getLeftPosCached() +
        Get the cached position of the left side of the drive.
        + + + +java.lang.Double getLeftVel()
        Get the velocity of the left side of the drive.
        - + +java.lang.Double +getLeftVelCached() +
        Get the cached velocity of the left side of the drive.
        + + + +java.lang.Double +getRightPos() +
        Get the position of the right side of the drive.
        + + + +java.lang.Double +getRightPosCached() +
        Get the cached position of the right side of the drive.
        + + + java.lang.Double getRightVel()
        Get the velocity of the right side of the drive.
        - + +java.lang.Double +getRightVelCached() +
        Get the cached velocity of the right side of the drive.
        + + + protected void initDefaultCommand()
        Initialize the default command for a subsystem.
        - + +void +resetPosition() +
        Reset the position of the drive if it has encoders.
        + + + void setOutput(double left, double right)
        Set the output of each side of the drive.
        + +void +update() +
        Updates all cached values with current ones.
        + + @@ -320,7 +368,109 @@

        getRightVel

        Specified by:
        getRightVel in interface DriveUnidirectional
        Returns:
        -
        The signed velocity in rotations per second, or null if the drive doesn't have encoders.
        +
        The signed velocity in feet per second, or null if the drive doesn't have encoders.
        + +
      • +

      + + + +
        +
      • +

        getLeftPos

        +
        @Nullable
        +public java.lang.Double getLeftPos()
        +
        Get the position of the left side of the drive.
        +
        +
        Specified by:
        +
        getLeftPos in interface DriveUnidirectional
        +
        Returns:
        +
        The signed position in feet, or null if the drive doesn't have encoders.
        +
        +
      • +
      + + + +
        +
      • +

        getRightPos

        +
        @Nullable
        +public java.lang.Double getRightPos()
        +
        Get the position of the right side of the drive.
        +
        +
        Specified by:
        +
        getRightPos in interface DriveUnidirectional
        +
        Returns:
        +
        The signed position in feet, or null if the drive doesn't have encoders.
        +
        +
      • +
      + + + +
        +
      • +

        getLeftVelCached

        +
        @Nullable
        +public java.lang.Double getLeftVelCached()
        +
        Get the cached velocity of the left side of the drive.
        +
        +
        Specified by:
        +
        getLeftVelCached in interface DriveUnidirectional
        +
        Returns:
        +
        The signed velocity in feet per second, or null if the drive doesn't have encoders.
        +
        +
      • +
      + + + +
        +
      • +

        getRightVelCached

        +
        @Nullable
        +public java.lang.Double getRightVelCached()
        +
        Get the cached velocity of the right side of the drive.
        +
        +
        Specified by:
        +
        getRightVelCached in interface DriveUnidirectional
        +
        Returns:
        +
        The signed velocity in feet per second, or null if the drive doesn't have encoders.
        +
        +
      • +
      + + + +
        +
      • +

        getLeftPosCached

        +
        @Nullable
        +public java.lang.Double getLeftPosCached()
        +
        Get the cached position of the left side of the drive.
        +
        +
        Specified by:
        +
        getLeftPosCached in interface DriveUnidirectional
        +
        Returns:
        +
        The signed position in feet, or null if the drive doesn't have encoders.
        +
        +
      • +
      + + + +
        +
      • +

        getRightPosCached

        +
        @Nullable
        +public java.lang.Double getRightPosCached()
        +
        Get the cached position of the right side of the drive.
        +
        +
        Specified by:
        +
        getRightPosCached in interface DriveUnidirectional
        +
        Returns:
        +
        The signed position in feet, or null if the drive doesn't have encoders.
      @@ -341,7 +491,7 @@

      fullStop

      -
        +
        • enableMotors

          public void enableMotors()
          @@ -352,6 +502,34 @@

          enableMotors

        + + + +
          +
        • +

          resetPosition

          +
          public void resetPosition()
          +
          Reset the position of the drive if it has encoders.
          +
          +
          Specified by:
          +
          resetPosition in interface DriveSubsystem
          +
          +
        • +
        + + + +
          +
        • +

          update

          +
          public void update()
          +
          Updates all cached values with current ones.
          +
          +
          Specified by:
          +
          update in interface Updatable
          +
          +
        • +
      diff --git a/docs/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineNominalVoltage.html b/docs/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineNominalVoltage.html index 0f672141..4cb0b05a 100644 --- a/docs/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineNominalVoltage.html +++ b/docs/org/usfirst/frc/team449/robot/drive/unidirectional/commands/DetermineNominalVoltage.html @@ -2,9 +2,9 @@ - + DetermineNominalVoltage (RoboRIO 1.0 API) - + @@ -49,7 +49,7 @@
    @@ -225,7 +230,7 @@

    getData

    -
      +
      • isVelocityOnly

        public boolean isVelocityOnly()
        @@ -235,6 +240,19 @@

        isVelocityOnly

      + + + +
        +
      • +

        isInverted

        +
        public boolean isInverted()
        +
        +
        Returns:
        +
        Whether or not the profile is inverted because we're driving it backwards.
        +
        +
      • +
    diff --git a/docs/org/usfirst/frc/team449/robot/other/Polynomial.html b/docs/org/usfirst/frc/team449/robot/other/Polynomial.html index 8cd41795..806c81ff 100644 --- a/docs/org/usfirst/frc/team449/robot/other/Polynomial.html +++ b/docs/org/usfirst/frc/team449/robot/other/Polynomial.html @@ -2,9 +2,9 @@ - + Polynomial (RoboRIO 1.0 API) - + @@ -49,7 +49,7 @@