Skip to content

Commit

Permalink
Remove DriveConstants static imports
Browse files Browse the repository at this point in the history
  • Loading branch information
rbrott committed Oct 27, 2018
1 parent 1e45908 commit 8e19e84
Show file tree
Hide file tree
Showing 8 changed files with 21 additions and 43 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -9,12 +9,6 @@
import com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints;
import com.acmerobotics.roadrunner.trajectory.constraints.MecanumConstraints;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.BASE_CONSTRAINTS;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.TRACK_WIDTH;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kA;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kStatic;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kV;

public abstract class SampleMecanumDriveBase extends MecanumDrive {
public static PIDCoefficients TRANSLATIONAL_PID = new PIDCoefficients(0, 0, 0);
public static PIDCoefficients HEADING_PID = new PIDCoefficients(0, 0, 0);
Expand All @@ -24,10 +18,11 @@ public abstract class SampleMecanumDriveBase extends MecanumDrive {
private TrajectoryFollower follower;

public SampleMecanumDriveBase() {
super(TRACK_WIDTH);
super(DriveConstants.TRACK_WIDTH);

constraints = new MecanumConstraints(BASE_CONSTRAINTS, TRACK_WIDTH);
follower = new MecanumPIDVAFollower(this, TRANSLATIONAL_PID, HEADING_PID, kV, kA, kStatic);
constraints = new MecanumConstraints(DriveConstants.BASE_CONSTRAINTS, DriveConstants.TRACK_WIDTH);
follower = new MecanumPIDVAFollower(this, TRANSLATIONAL_PID, HEADING_PID,
DriveConstants.kV, DriveConstants.kA, DriveConstants.kStatic);
}

public TrajectoryBuilder trajectoryBuilder() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,6 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

public class SampleMecanumDriveOptimized extends SampleMecanumDriveBase {
private ExpansionHubEx hub;
private ExpansionHubMotor leftFront, leftRear, rightRear, rightFront;
Expand Down Expand Up @@ -88,7 +86,7 @@ public List<Double> getWheelPositions() {
RevBulkData bulkData = hub.getBulkInputData();
List<Double> wheelPositions = new ArrayList<>();
for (ExpansionHubMotor motor : motors) {
wheelPositions.add(encoderTicksToInches(bulkData.getMotorCurrentPosition(motor)));
wheelPositions.add(DriveConstants.encoderTicksToInches(bulkData.getMotorCurrentPosition(motor)));
}
return wheelPositions;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,6 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

public class SampleMecanumDriveSimple extends SampleMecanumDriveBase {
private DcMotorEx leftFront, leftRear, rightRear, rightFront;
private List<DcMotorEx> motors;
Expand Down Expand Up @@ -76,7 +74,7 @@ public void setPIDFCoefficients(DcMotor.RunMode runMode, PIDFCoefficients coeffi
public List<Double> getWheelPositions() {
List<Double> wheelPositions = new ArrayList<>();
for (DcMotorEx motor : motors) {
wheelPositions.add(encoderTicksToInches(motor.getCurrentPosition()));
wheelPositions.add(DriveConstants.encoderTicksToInches(motor.getCurrentPosition()));
}
return wheelPositions;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,6 @@
import com.acmerobotics.roadrunner.trajectory.constraints.DriveConstraints;
import com.acmerobotics.roadrunner.trajectory.constraints.TankConstraints;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.BASE_CONSTRAINTS;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.TRACK_WIDTH;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kA;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kStatic;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kV;

@Config
public abstract class SampleTankDriveBase extends TankDrive {
public static PIDCoefficients DISPLACEMENT_PID = new PIDCoefficients(0, 0, 0);
Expand All @@ -26,10 +20,11 @@ public abstract class SampleTankDriveBase extends TankDrive {
private TrajectoryFollower follower;

public SampleTankDriveBase() {
super(TRACK_WIDTH);
super(DriveConstants.TRACK_WIDTH);

constraints = new TankConstraints(BASE_CONSTRAINTS, TRACK_WIDTH);
follower = new TankPIDVAFollower(this, DISPLACEMENT_PID, CROSS_TRACK_PID, kV, kA, kStatic);
constraints = new TankConstraints(DriveConstants.BASE_CONSTRAINTS, DriveConstants.TRACK_WIDTH);
follower = new TankPIDVAFollower(this, DISPLACEMENT_PID, CROSS_TRACK_PID,
DriveConstants.kV, DriveConstants.kA, DriveConstants.kStatic);
}

public TrajectoryBuilder trajectoryBuilder() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,6 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

public class SampleTankDriveOptimized extends SampleTankDriveBase {
private ExpansionHubEx hub;
private List<ExpansionHubMotor> motors, leftMotors, rightMotors;
Expand Down Expand Up @@ -87,10 +85,10 @@ public List<Double> getWheelPositions() {
double leftSum = 0, rightSum = 0;
RevBulkData bulkData = hub.getBulkInputData();
for (DcMotorEx leftMotor : leftMotors) {
leftSum += encoderTicksToInches(bulkData.getMotorCurrentPosition(leftMotor));
leftSum += DriveConstants.encoderTicksToInches(bulkData.getMotorCurrentPosition(leftMotor));
}
for (DcMotorEx rightMotor : rightMotors) {
rightSum += encoderTicksToInches(bulkData.getMotorCurrentPosition(rightMotor));
rightSum += DriveConstants.encoderTicksToInches(bulkData.getMotorCurrentPosition(rightMotor));
}
return Arrays.asList(leftSum / leftMotors.size(), rightSum / rightMotors.size());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -13,8 +13,6 @@
import java.util.Arrays;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.encoderTicksToInches;

public class SampleTankDriveSimple extends SampleTankDriveBase {
private List<DcMotorEx> motors, leftMotors, rightMotors;
private BNO055IMU imu;
Expand Down Expand Up @@ -77,10 +75,10 @@ public void setPIDFCoefficients(DcMotor.RunMode runMode, PIDFCoefficients coeffi
public List<Double> getWheelPositions() {
double leftSum = 0, rightSum = 0;
for (DcMotorEx leftMotor : leftMotors) {
leftSum += encoderTicksToInches(leftMotor.getCurrentPosition());
leftSum += DriveConstants.encoderTicksToInches(leftMotor.getCurrentPosition());
}
for (DcMotorEx rightMotor : rightMotors) {
rightSum += encoderTicksToInches(rightMotor.getCurrentPosition());
rightSum += DriveConstants.encoderTicksToInches(rightMotor.getCurrentPosition());
}
return Arrays.asList(leftSum / leftMotors.size(), rightSum / rightMotors.size());
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,14 +15,12 @@
import com.qualcomm.robotcore.hardware.PIDFCoefficients;
import com.qualcomm.robotcore.util.RobotLog;

import org.firstinspires.ftc.teamcode.drive.DriveConstants;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDriveSimple;

import java.util.ArrayList;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.BASE_CONSTRAINTS;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.kV;

/*
* This routine is designed to tune the PIDF coefficients used by the REV Expansion Hubs for closed-
* loop velocity control. Although it may seem unnecessary, tuning these coefficients is just as
Expand Down Expand Up @@ -90,18 +88,18 @@ public void runOpMode() {
activeProfile = MotionProfileGenerator.generateMotionProfile(start, goal, new MotionConstraints() {
@Override
public double maximumVelocity(double v) {
return BASE_CONSTRAINTS.maximumVelocity;
return DriveConstants.BASE_CONSTRAINTS.maximumVelocity;
}

@Override
public double maximumAcceleration(double v) {
return BASE_CONSTRAINTS.maximumAcceleration;
return DriveConstants.BASE_CONSTRAINTS.maximumAcceleration;
}
});
profileStartTimestamp = clock.seconds();
}
MotionState motionState = activeProfile.get(profileTime);
double targetPower = kV * motionState.getV();
double targetPower = DriveConstants.kV * motionState.getV();
drive.setVelocity(new Pose2d(targetPower, 0, 0));

List<Double> wheelPositions = drive.getWheelPositions();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,12 @@
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;

import org.apache.commons.math3.stat.regression.SimpleRegression;
import org.firstinspires.ftc.teamcode.drive.DriveConstants;
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDriveSimple;

import java.util.ArrayList;
import java.util.List;

import static org.firstinspires.ftc.teamcode.drive.DriveConstants.GEAR_RATIO;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.MOTOR_CONFIG;
import static org.firstinspires.ftc.teamcode.drive.DriveConstants.WHEEL_RADIUS;

/*
* Op mode for computing kV, kStatic, and kA from various drive routines. Note: for those using the
* built-in PID, **kStatic and kA should not be tuned**. For the curious, here's an outline of the
Expand Down Expand Up @@ -94,7 +91,8 @@ public void runOpMode() throws InterruptedException {
telemetry.log().add("Running...");
telemetry.update();

double maxVel = MOTOR_CONFIG.getMaxRPM() * GEAR_RATIO * 2 * Math.PI * WHEEL_RADIUS / 60.0;
double maxRpm = DriveConstants.MOTOR_CONFIG.getMaxRPM();
double maxVel = maxRpm * DriveConstants.GEAR_RATIO * 2 * Math.PI * DriveConstants.WHEEL_RADIUS / 60.0;
double finalVel = MAX_POWER * maxVel;
double accel = (finalVel * finalVel) / (2.0 * DISTANCE);
double rampTime = Math.sqrt(2.0 * DISTANCE / accel);
Expand Down

0 comments on commit 8e19e84

Please sign in to comment.