Skip to content

Commit

Permalink
auto!
Browse files Browse the repository at this point in the history
  • Loading branch information
richpant committed Nov 5, 2024
1 parent c99a699 commit 7ab574b
Show file tree
Hide file tree
Showing 5 changed files with 26 additions and 26 deletions.
10 changes: 5 additions & 5 deletions TeamCode/src/main/java/indubitables/config/runmodes/Auto.java
Original file line number Diff line number Diff line change
Expand Up @@ -193,11 +193,11 @@ public void buildPaths() {
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(new BezierLine(new Point(56.000, 16.000, Point.CARTESIAN),new Point(24, 16.000, Point.CARTESIAN)))
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(new BezierCurve(new Point(24, 16.000, Point.CARTESIAN), new Point(56.000, 16.000, Point.CARTESIAN), new Point(56.000, 9.50, Point.CARTESIAN)))
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(new BezierLine(new Point(56.000, 9.50, Point.CARTESIAN), new Point(24, 9.5, Point.CARTESIAN)))
.setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(new BezierLine(new Point(24, 9.5, Point.CARTESIAN), new Point(blueObservationSpecimenSetPose)))
// .addPath(new BezierCurve(new Point(24, 16.000, Point.CARTESIAN), new Point(56.000, 16.000, Point.CARTESIAN), new Point(56.000, 9.50, Point.CARTESIAN)))
// .setConstantHeadingInterpolation(Math.toRadians(0))
// .addPath(new BezierLine(new Point(56.000, 9.50, Point.CARTESIAN), new Point(24, 9.5, Point.CARTESIAN)))
// .setConstantHeadingInterpolation(Math.toRadians(0))
.addPath(new BezierLine(new Point(24, 16, Point.CARTESIAN), new Point(blueObservationSpecimenSetPose)))
.setLinearHeadingInterpolation(Math.toRadians(0), blueObservationSpecimenSetPose.getHeading())
.build();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ public enum RobotStart {

// Preload Poses
public static final Pose blueBucketPreloadPose = new Pose(30.25, 78.375, Math.toRadians(180));
public static final Pose blueObservationPreloadPose = new Pose(30.25, 65.625, Math.toRadians(180));
public static final Pose blueObservationPreloadPose = new Pose(30.25, 63.625, Math.toRadians(180));
public static final Pose redBucketPreloadPose = new Pose(144-blueBucketPreloadPose.getX(), blueBucketPreloadPose.getY(), 0);
public static final Pose redObservationPreloadPose = new Pose(144-blueObservationPreloadPose.getX(), blueObservationPreloadPose.getY(), 0);

Expand All @@ -40,11 +40,11 @@ public enum RobotStart {
public static final Pose blueObservationElement2ControlPose = new Pose(20, 96);
public static final Pose blueObservationElement3Pose = new Pose(20, 96, Math.toRadians(180));
public static final Pose blueObservationElement3ControlPose = new Pose(20, 110);
public static final Pose blueObservationSpecimenSetPose = new Pose(22, 27.5, Math.toRadians(0));
public static final Pose blueObservationSpecimenPickupPose = new Pose(17, 27.5, Math.toRadians(0));
public static final Pose blueObservationSpecimenPickup2Pose = new Pose(18.5, 27.5, Math.toRadians(0));
public static final Pose blueObservationSpecimen1Pose = new Pose(30.25, 70.625, Math.toRadians(180));
public static final Pose blueObservationSpecimen2Pose = new Pose(30.25, 73.625, Math.toRadians(180));
public static final Pose blueObservationSpecimenSetPose = new Pose(22, 27, Math.toRadians(0));
public static final Pose blueObservationSpecimenPickupPose = new Pose(17, 27, Math.toRadians(0));
public static final Pose blueObservationSpecimenPickup2Pose = new Pose(17, 27, Math.toRadians(0));
public static final Pose blueObservationSpecimen1Pose = new Pose(29.75, 68.625, Math.toRadians(180));
public static final Pose blueObservationSpecimen2Pose = new Pose(29.75, 71.625, Math.toRadians(180));
public static final Pose blueObservationSpecimen3Pose = new Pose(30.25, 76.625, Math.toRadians(180));
public static final Pose blueObservationParkPose = new Pose(10, 24, 0);
public static final Pose blueObservationParkControlPose = new Pose(20, 50);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ public class RobotConstants {
public static double armInit = 0.15;

public static int liftToZero = 100;
public static int liftToHumanPlayer = 150;
public static int liftToHumanPlayer = 175;
public static int liftToHighChamber = 275;
public static int liftToHighChamber2 = 350;
public static int liftToHighChamber3 = 350;
Expand Down
12 changes: 6 additions & 6 deletions TeamCode/src/main/java/indubitables/opmode/BlueObservation.java
Original file line number Diff line number Diff line change
Expand Up @@ -95,7 +95,7 @@ public void pathUpdate() {
auto.liftPIDF = true;
auto.lift.rightLift.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
auto.lift.rightLift.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
auto.follower.setMaxPower(1);
auto.follower.setMaxPower(0.8);
auto.follower.followPath(auto.specimen1, true);
setPathState(8); }
break;
Expand All @@ -119,24 +119,24 @@ public void pathUpdate() {
break;
case 11: //Begins the path for grab 2 & closes the claw once it reaches position and passes 0.75 seconds
if(auto.actionNotBusy() && !auto.follower.isBusy()) {
auto.follower.setMaxPower(0.7);
auto.follower.setMaxPower(0.65);
auto.follower.followPath(auto.grab2, true);
if(pathTimer.getElapsedTimeSeconds() > 2.5) {
if(pathTimer.getElapsedTimeSeconds() > 2.75) {
auto.claw.close();
setPathState(12); } }
break;
case 12: //Waits 0.25 seconds and puts robot in neutral position
if(pathTimer.getElapsedTimeSeconds() > 0.25) {
if(pathTimer.getElapsedTimeSeconds() > 0.5) {
auto.init();
setPathState(13); }
break;
case 13: //Drives to chamber once action finishes
auto.follower.setMaxPower(1);
auto.follower.setMaxPower(0.8);
auto.follower.followPath(auto.specimen2, true);
setPathState(14);
break;
case 14: //Starts the Chamber State Machine
if(pathTimer.getElapsedTimeSeconds() > 0.5) {
if(pathTimer.getElapsedTimeSeconds() > 1.5) {
auto.startChamber();
setPathState(15); }
break;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,9 +38,9 @@ public class FollowerConstants {

// Translational PIDF coefficients (don't use integral)
public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients(
0.1,
0,
0.3,
0,
0.0001,
0);

// Translational Integral
Expand All @@ -56,7 +56,7 @@ public class FollowerConstants {

// Heading error PIDF coefficients
public static CustomPIDFCoefficients headingPIDFCoefficients = new CustomPIDFCoefficients(
0.5,
0.9,
0,
0,
0);
Expand Down Expand Up @@ -165,9 +165,9 @@ public class FollowerConstants {

// Secondary translational PIDF coefficients (don't use integral)
public static CustomPIDFCoefficients secondaryTranslationalPIDFCoefficients = new CustomPIDFCoefficients(
0.3,
0.4,
0,
0.01,
0.0001,
0);

// Secondary translational Integral value
Expand All @@ -186,9 +186,9 @@ public class FollowerConstants {

// Secondary heading error PIDF coefficients
public static CustomPIDFCoefficients secondaryHeadingPIDFCoefficients = new CustomPIDFCoefficients(
3,
4.5,
0,
0.085,
0.0001,
0);

// Feed forward constant added on to the secondary heading PIDF
Expand All @@ -200,7 +200,7 @@ public class FollowerConstants {

// Secondary drive PIDF coefficients
public static CustomFilteredPIDFCoefficients secondaryDrivePIDFCoefficients = new CustomFilteredPIDFCoefficients(
0.005,
0.011,
0.0001,
0.0005,
0.6,
Expand Down

0 comments on commit 7ab574b

Please sign in to comment.