Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Blue bottom meep meep latest #12

Open
wants to merge 3 commits into
base: meepmeeptesting
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
import com.noahbres.meepmeep.roadrunner.DefaultBotBuilder;
import com.noahbres.meepmeep.roadrunner.entity.RoadRunnerBotEntity;

import java.util.Vector;

public class BlueBottomMeepMeep {

public static void main(String[] args) {
Expand All @@ -20,30 +22,87 @@ public static void main(String[] args) {
.setConstraints(60, 60, Math.toRadians(180), Math.toRadians(180), 15)
.setColorScheme(new ColorSchemeBlueDark())
.followTrajectorySequence(drive ->
drive.trajectorySequenceBuilder(new Pose2d(-36,60, Math.toRadians(-90)))
.lineToLinearHeading(new Pose2d(-35,-32, Math.toRadians(180)))
drive.trajectorySequenceBuilder(new Pose2d(-36,-60, Math.toRadians(90)))
/* BBM .back(25)
.forward(10)
.splineToConstantHeading(new Vector2d(-54,24),Math.toRadians(-90))
.splineToLinearHeading(new Pose2d(-30,8, Math.toRadians(90)),Math.toRadians(0))
.turn(Math.toRadians(-90))
.lineToConstantHeading(new Vector2d(15,8))
.splineToLinearHeading(new Pose2d(40,36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, 36, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, 60))
.lineTo(new Vector2d(60, 60)) */

/* RBM .forward(25)
.back(10)
.splineToConstantHeading(new Vector2d(-54,-24),Math.toRadians(90))
.splineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(90)),Math.toRadians(180))
.turn(Math.toRadians(-90))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, -36, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60)) */

/* BBR .lineToLinearHeading(new Pose2d(-36,34, Math.toRadians(90)))
.turn(Math.toRadians(90))
.back(4)
.forward(10)
.lineToLinearHeading(new Pose2d(-36,8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,8))
.splineToLinearHeading(new Pose2d(40,36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, 30, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, 60))
.lineTo(new Vector2d(60, 60))
*/

/* RBR .lineToLinearHeading(new Pose2d(-36,-34, Math.toRadians(90)))
.turn(Math.toRadians(90))
.back(4)
.forward(4)

.lineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(180)))
.lineToLinearHeading(new Pose2d(10,-8, Math.toRadians(180)))
.splineTo(new Vector2d(40,-36), Math.toRadians(0))

.lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(0)))

.lineTo(new Vector2d(52, -60))
.lineTo(new Vector2d(60, -60))

// .lineToLinearHeading(new Pose2d(-35,-32, Math.toRadians(180)))
// .back(4)
// .forward(4)
//
// .lineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(180)))
// .lineToLinearHeading(new Pose2d(10,-8, Math.toRadians(180)))
// .splineTo(new Vector2d(40,-36), Math.toRadians(0))
// .lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(180)))
// .lineTo(new Vector2d(52, -60))
// .lineTo(new Vector2d(60, -60))
.forward(10)
.lineToLinearHeading(new Pose2d(-36,-8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, -42, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60))*/





/*BBL .strafeLeft(10)
.lineToLinearHeading(new Pose2d(-46,38, Math.toRadians(90)))
.forward(10)
.strafeRight(10)
.lineToLinearHeading(new Pose2d(-36,8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,8))
.splineToLinearHeading(new Pose2d(40,36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, 42, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, 60))
.lineTo(new Vector2d(60, 60)) */

/* RBL .strafeLeft(10)
.lineToLinearHeading(new Pose2d(-46,-38, Math.toRadians(90)))
.forward(10)
.strafeRight(10)
.lineToLinearHeading(new Pose2d(-36,-8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(180)))
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60))*/




.build());

meepMeep.setBackground(MeepMeep.Background.FIELD_CENTERSTAGE_JUICE_DARK)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ public class BlueBottom extends AutonBase {
public void runOpMode() {

double distFromAprilTagX, distFromAprilTagForward;
Pose2d startPos = new Pose2d(-36,-60, Math.toRadians(-90));
Pose2d startPos = new Pose2d(-36,-60, Math.toRadians(90));

waitForStart();

Expand All @@ -42,28 +42,67 @@ public void runOpMode() {
switch (pos) {
case LEFT:
traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.lineToLinearHeading(new Pose2d(-35,-32, Math.toRadians(180)))
.back(4)
.forward(4)
.strafeLeft(10)
.lineToLinearHeading(new Pose2d(-46,38, Math.toRadians(90)))
.forward(10)
.strafeRight(10)
.build();
traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.lineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(180)))
.lineToLinearHeading(new Pose2d(10,-8, Math.toRadians(180)))
.splineTo(new Vector2d(40,-36), Math.toRadians(0))
.lineToLinearHeading(new Pose2d(-36,8, Math.toRadians(180)))
.lineToLinearHeading(new Pose2d(15,8, Math.toRadians(180)))
.splineToLinearHeading(new Pose2d(40,36, Math.toRadians(180)),Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(0)))
.lineToSplineHeading(new Pose2d(52, 42, Math.toRadians(0)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.lineTo(new Vector2d(52, -60))
.lineTo(new Vector2d(60, -60))
.lineTo(new Vector2d(52, 60))
.lineTo(new Vector2d(60, 60))
.build();
break;
case RIGHT:
traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.lineToLinearHeading(new Pose2d(-36,34, Math.toRadians(90)))
.turn(Math.toRadians(90))
.back(4)
.forward(10)
.build();

traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.lineToLinearHeading(new Pose2d(-36,8, Math.toRadians(180)))
.lineToLinearHeading(new Pose2d(15,8, Math.toRadians(180)))
.splineToLinearHeading(new Pose2d(40,36, Math.toRadians(180)),Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, 30, Math.toRadians(0)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.forward(6)
.lineTo(new Vector2d(46, 60))
.lineTo(new Vector2d(60, 60))
.build();
break;

case MIDDLE:
traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.back(25)
.forward(10)
.splineToConstantHeading(new Vector2d(-54,24),Math.toRadians(-90))
.splineToLinearHeading(new Pose2d(-30,8, Math.toRadians(90)),Math.toRadians(0))
.build();
traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.turn(Math.toRadians(-90))
.lineToLinearHeading(new Pose2d(15,8, Math.toRadians(180)))
.splineToLinearHeading(new Pose2d(40,36, Math.toRadians(180)),Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, 36, Math.toRadians(180)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.forward(6)
.lineTo(new Vector2d(46, 60))
.lineTo(new Vector2d(60, 60))
.build();

break;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,28 +42,66 @@ public void runOpMode() {
switch (pos) {
case LEFT:
traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.lineToLinearHeading(new Pose2d(-35,-32, Math.toRadians(180)))
.back(4)
.forward(4)
.strafeLeft(10)
.lineToLinearHeading(new Pose2d(-46,-38, Math.toRadians(90)))
.forward(10)
.strafeRight(10)
.build();
traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.lineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(180)))
.lineToLinearHeading(new Pose2d(10,-8, Math.toRadians(180)))
.splineTo(new Vector2d(40,-36), Math.toRadians(0))
.lineToLinearHeading(new Pose2d(-36,-8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(0)))
.lineToSplineHeading(new Pose2d(52, -30, Math.toRadians(180)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.lineTo(new Vector2d(52, -60))
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60))
.build();
break;
case RIGHT:

traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.turn(Math.toRadians(90))
.back(4)
.forward(10)
.build();
traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.lineToLinearHeading(new Pose2d(-36,-8, Math.toRadians(0)))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, -42, Math.toRadians(180)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60))
.build();
break;

case MIDDLE:
traj_pushPixel = robot.roadRunner.trajectorySequenceBuilder(startPos)
.forward(25)
.back(10)
.splineToConstantHeading(new Vector2d(-54,-24),Math.toRadians(90))
.splineToLinearHeading(new Pose2d(-30,-8, Math.toRadians(90)),Math.toRadians(180))
.build();
traj_toBackboard = robot.roadRunner.trajectorySequenceBuilder(traj_pushPixel.end())
.turn(Math.toRadians(-90))
.lineToConstantHeading(new Vector2d(15,-8))
.splineToLinearHeading(new Pose2d(40,-36,Math.toRadians(180)), Math.toRadians(0))
.build();
traj_placePixel = robot.roadRunner.trajectorySequenceBuilder(traj_toBackboard.end())
.lineToSplineHeading(new Pose2d(52, -36, Math.toRadians(180)))
.build();
traj_park = robot.roadRunner.trajectorySequenceBuilder(traj_placePixel.end())
.forward(6)
.lineTo(new Vector2d(46, -60))
.lineTo(new Vector2d(60, -60))
.build();

break;
}
Expand Down