Skip to content

Commit

Permalink
Merge branch 'new-structure' of https://github.com/ftc13100/IntoTheDe…
Browse files Browse the repository at this point in the history
…ep-2025 into new-structure
  • Loading branch information
AdityaP241 committed Dec 26, 2024
2 parents 202f987 + 21926fb commit 4fa1dc0
Show file tree
Hide file tree
Showing 13 changed files with 402 additions and 123 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
package com.example.meepmeeptesting

import com.acmerobotics.roadrunner.Pose2d
import com.acmerobotics.roadrunner.Vector2d
import com.noahbres.meepmeep.MeepMeep
import com.noahbres.meepmeep.MeepMeep.Background
import com.noahbres.meepmeep.core.toRadians
import com.noahbres.meepmeep.roadrunner.DefaultBotBuilder

object Sample1Plus3Testing {
@JvmStatic
fun main(args: Array<String>) {
val meepMeep = MeepMeep(800)

val myBot =
DefaultBotBuilder(meepMeep) // Set bot constraints: maxVel, maxAccel, maxAngVel, maxAngAccel, track width
.setConstraints(50.0, 50.0, Math.toRadians(180.0), Math.toRadians(180.0), 4669.698132939092 * 0.002953423066)
.build()

myBot.runAction(
myBot.drive.actionBuilder(Pose2d(10.0, 62.0, -90.0.toRadians()))
.setTangent(-45.0)
.splineToLinearHeading(Pose2d(56.0, 56.0, Math.toRadians(225.0)), Math.toRadians(45.0))
.turn(Math.toRadians(30.0))
.turn(Math.toRadians(-30.0))
.turn(Math.toRadians(55.0))
.turn(Math.toRadians(-55.0))
.turn(Math.toRadians(75.0))
.build()

)

meepMeep.setBackground(Background.FIELD_INTO_THE_DEEP_JUICE_DARK)
.setDarkMode(true)
.setBackgroundAlpha(0.95f)
.addEntity(myBot)
.start()
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ import com.noahbres.meepmeep.MeepMeep.Background
import com.noahbres.meepmeep.core.toRadians
import com.noahbres.meepmeep.roadrunner.DefaultBotBuilder

object MeepMeepTesting {
object Specimen1Plus3Testing {
@JvmStatic
fun main(args: Array<String>) {
val meepMeep = MeepMeep(800)
Expand All @@ -21,22 +21,21 @@ object MeepMeepTesting {
myBot.drive.actionBuilder(Pose2d(-10.0, 62.0, 90.0.toRadians()))
.strafeToConstantHeading(Vector2d(2.0, 31.5))
.setTangent(90.0.toRadians())
.splineToSplineHeading(Pose2d(-36.0, 35.0, 0.0), -90.0.toRadians())
.splineToLinearHeading(Pose2d(-36.0, 35.0, Math.toRadians(90.0)), -90.0.toRadians())
.setTangent(-90.0.toRadians())
.splineToSplineHeading(Pose2d(-44.0, 5.0, 0.0.toRadians()), 120.0.toRadians())
.splineToLinearHeading(Pose2d(-44.0, 5.0, 90.0.toRadians()), 120.0.toRadians())
.strafeTo(Vector2d(-44.0, 56.0))
.setTangent(-90.0.toRadians())
.splineToSplineHeading( Pose2d(-56.0, 5.0, 0.0.toRadians()), 130.0.toRadians())
.splineToLinearHeading( Pose2d(-56.0, 5.0, 90.0.toRadians()), 130.0.toRadians())
.strafeTo(Vector2d(-56.0, 56.0))
.setTangent(-90.0.toRadians())
.splineToSplineHeading(Pose2d(-50.0, 50.0, 90.0.toRadians()), Math.toRadians(90.0))
.splineToLinearHeading(Pose2d(-34.0, 48.0, 180.0.toRadians()), Math.toRadians(90.0))
.setTangent(90.0.toRadians())
.splineToSplineHeading(Pose2d(-36.0, 59.0, 180.0.toRadians()), Math.toRadians(180.0))
// .setTangent(180.0.toRadians())
// .splineToLinearHeading(Pose2d(0.0, 34.0, 90.0.toRadians()), -90.0.toRadians())
// .setTangent(0.0.toRadians())
// .splineToSplineHeading(Pose2d(-36.0, 59.0, 180.0.toRadians()), 0.0)
// .setTangent(180.0.toRadians())
.strafeTo(Vector2d(-34.0, 59.0))
.splineToLinearHeading(Pose2d(0.0, 34.0, 90.0.toRadians()), -90.0.toRadians())
.setTangent(0.0.toRadians())
.splineToSplineHeading(Pose2d(-34.0, 59.0, 180.0.toRadians()), 0.0)
.setTangent(180.0.toRadians())
// .splineToLinearHeading(Pose2d(0.0, 34.0, 90.0.toRadians()), -90.0.toRadians())
// .setTangent(0.0.toRadians())
// .splineToSplineHeading(Pose2d(-36.0, 59.0, 180.0.toRadians()), 0.0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,6 @@ class DriveCommand(
private val leftY: () -> Double,
private val rightX: () -> Double,
private val zoneVal: Double,
private val multiplier: Double = 0.9,
) : CommandBase() {

init {
Expand All @@ -19,9 +18,9 @@ class DriveCommand(

override fun execute() {
subsystem.drive(
leftY = zonedDrive(leftY.invoke() * multiplier, zoneVal).pow(3),
leftX = zonedDrive(leftX.invoke() * multiplier, zoneVal).pow(3),
rightX = zonedDrive(rightX.invoke() * multiplier, zoneVal).pow(3),
leftY = zonedDrive(leftY.invoke(), zoneVal).pow(3),
leftX = zonedDrive(leftX.invoke(), zoneVal).pow(3),
rightX = zonedDrive(rightX.invoke(), zoneVal).pow(3),
)
}

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package org.firstinspires.ftc.teamcode.commands.intake

import com.arcrobotics.ftclib.command.CommandBase
import org.firstinspires.ftc.teamcode.subsystems.intake.IntakeSubsystem

class ThrowbackCommand(
private val subsystem: IntakeSubsystem
) : CommandBase() {
override fun execute() = subsystem.wristUp()

override fun isFinished() = subsystem.isPressed

override fun end(interrupted: Boolean) = subsystem.reset()
}
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ import com.acmerobotics.roadrunner.Pose2d
enum class AutoStartPose(val startPose: Pose2d) {
BLUE_LEFT(
Pose2d(
38.0, 62.0, Math.toRadians(270.0)
10.0, 62.0, Math.toRadians(-90.0)
)
),

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,9 +9,9 @@ enum class ControlBoard(val deviceName: String) {
DRIVE_RIGHT_REAR("rightRear"),

// Odometry
ODO_LEFT_ENCODER("leftFront"),
ODO_LEFT_ENCODER("rightSlideString"),
ODO_RIGHT_ENCODER("rightFront"),
ODO_STRAFE_ENCODER("leftSlideString"),
ODO_STRAFE_ENCODER("rightSlideAxel"),

// Arm
ARM_LEFT("leftSlideAxel"),
Expand All @@ -22,7 +22,6 @@ enum class ControlBoard(val deviceName: String) {
//Intake
INTAKE("intakeRoller"),
INTAKE_BELT("intakeBelt"),
INTAKE_ENCODER("leftSlideAxel"),


INTAKE_ENCODER("leftFront"),
INTAKE_TOUCH("intakeTouch"),
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,55 @@
package org.firstinspires.ftc.teamcode.opModes.auto

import com.acmerobotics.roadrunner.Action
import com.acmerobotics.roadrunner.Pose2d
import com.acmerobotics.roadrunner.Vector2d
import com.arcrobotics.ftclib.command.CommandOpMode
import com.arcrobotics.ftclib.command.InstantCommand
import com.arcrobotics.ftclib.command.ParallelCommandGroup
import com.arcrobotics.ftclib.command.SequentialCommandGroup
import com.arcrobotics.ftclib.command.WaitCommand
import com.qualcomm.robotcore.eventloop.opmode.Autonomous
import org.firstinspires.ftc.teamcode.commands.ActionCommand
import org.firstinspires.ftc.teamcode.commands.arm.ArmCommand
import org.firstinspires.ftc.teamcode.commands.elevator.ElevatorCommand
import org.firstinspires.ftc.teamcode.commands.intake.IntakeBeltCommand
import org.firstinspires.ftc.teamcode.commands.intake.IntakeCommand
import org.firstinspires.ftc.teamcode.constants.AutoStartPose
import org.firstinspires.ftc.teamcode.subsystems.arm.ArmSubsystem
import org.firstinspires.ftc.teamcode.subsystems.drive.DriveSubsystem
import org.firstinspires.ftc.teamcode.subsystems.intake.IntakeSubsystem
import org.firstinspires.ftc.teamcode.subsystems.slides.ElevatorSubsystem

@Autonomous(name = "Sample 1 + 3")
class Sample1Plus3 : CommandOpMode() {
override fun initialize() {
DriveSubsystem.initialize(hardwareMap)
ArmSubsystem.initialize(hardwareMap)
ElevatorSubsystem.initialize(hardwareMap)
IntakeSubsystem.initialize(hardwareMap)

val scorePreloaded =
SequentialCommandGroup(
InstantCommand({ DriveSubsystem.pose = AutoStartPose.BLUE_LEFT.startPose }),
ParallelCommandGroup(
ActionCommand(
DriveSubsystem.actionBuilder(AutoStartPose.BLUE_LEFT::startPose)
.setTangent(-45.0)
.splineToLinearHeading(Pose2d(56.0, 56.0, Math.toRadians(225.0)), Math.toRadians(45.0)) .build(),
DriveSubsystem
),
ArmCommand(Math.toRadians(90.0), ArmSubsystem).withTimeout(2000),
IntakeBeltCommand(Math.toRadians(-60.0),IntakeSubsystem),
InstantCommand({ IntakeSubsystem.closeClaw() }),
),
ElevatorCommand(30.0, ElevatorSubsystem).withTimeout(2000),
IntakeBeltCommand(Math.toRadians(90.0), IntakeSubsystem).withTimeout(1000),
InstantCommand({ IntakeSubsystem.openClaw() }),
)

schedule(
scorePreloaded
)
}

}
Loading

0 comments on commit 4fa1dc0

Please sign in to comment.