Skip to content

Commit 78780f2

Browse files
committed
States 🫡
GG, gl advancing teams
1 parent 3deae8d commit 78780f2

File tree

8 files changed

+49
-17
lines changed

8 files changed

+49
-17
lines changed

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/common/subsystems/intake/Diffy.kt‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -112,7 +112,7 @@ class Diffy(
112112
var kD = 0.0
113113

114114
@JvmField
115-
var transferPitch = -.25
115+
var transferPitch = -.325
116116

117117
@JvmField
118118
var transferRoll = .275
@@ -121,7 +121,7 @@ class Diffy(
121121
var hoverPitch = -.65
122122

123123
@JvmField
124-
var hoverRoll = -.3
124+
var hoverRoll = -.2
125125

126126
@JvmField
127127
var pickupPitch = -.6

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/common/subsystems/intake/IntakeArm.kt‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -60,7 +60,7 @@ class IntakeArm(
6060

6161
companion object {
6262
@JvmField
63-
var basePosition = 0.4
63+
var basePosition = 0.41
6464

6565
@JvmField
6666
var extendedPosition = 0.6

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/common/subsystems/outtake/OuttakeArm.kt‎

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -68,7 +68,7 @@ class OuttakeArm(
6868

6969
companion object {
7070
@JvmField
71-
var basePosition = 0.6
71+
var basePosition = 0.59
7272

7373
@JvmField
7474
var transferPosition = 0.62

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmodes/auton/SampleAuton.kt‎

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@ import com.arcrobotics.ftclib.command.SequentialCommandGroup
99
import com.arcrobotics.ftclib.command.WaitCommand
1010
import com.arcrobotics.ftclib.command.WaitUntilCommand
1111
import com.qualcomm.robotcore.eventloop.opmode.Autonomous
12+
import com.qualcomm.robotcore.util.ElapsedTime
1213
import org.firstinspires.ftc.teamcode.common.commands.outtake.SlidesCommand
1314
import org.firstinspires.ftc.teamcode.common.subsystems.outtake.OuttakeArmPosition
1415
import org.firstinspires.ftc.teamcode.common.subsystems.outtake.OuttakeWristPosition
@@ -17,10 +18,10 @@ import org.firstinspires.ftc.teamcode.common.utils.OpMode
1718
import org.firstinspires.ftc.teamcode.common.utils.Pose2d
1819
import org.firstinspires.ftc.teamcode.opmodes.teleop.MainTeleopBlue.Companion.outtakeDropArmDelay
1920

20-
@Autonomous(name = "Sample Auton", preselectTeleOp = "Main Teleop Red")
21+
@Autonomous(name = "Sample Auton", preselectTeleOp = "Main Teleop Blue")
2122
@Config
2223
@SuppressWarnings("detekt:MagicNumber", "detekt:SpreadOperator")
23-
class SampleAuton : OpMode() {
24+
open class SampleAuton : OpMode() {
2425
override val robot by lazy { AutonRobot(this) }
2526

2627
override fun initialize() {
@@ -44,10 +45,12 @@ class SampleAuton : OpMode() {
4445

4546
super.initialize()
4647

47-
val grab = {
48-
SequentialCommandGroup(
48+
fun grab(): SequentialCommandGroup {
49+
val timeOutCV = ElapsedTime()
50+
return SequentialCommandGroup(
51+
InstantCommand({ timeOutCV.reset() }),
4952
robot.autoPickup.startScanning(),
50-
WaitUntilCommand { robot.autoPickup.lastTarget != null },
53+
WaitUntilCommand { robot.autoPickup.lastTarget != null || timeOutCV.milliseconds() > timeOutCVDelay },
5154
robot.autoPickup.stopScanning(),
5255
robot.autoPickup.align(),
5356
robot.intake.grab(),
@@ -103,7 +106,7 @@ class SampleAuton : OpMode() {
103106
robot.macros.exitTransfer(),
104107
up().alongWith(
105108
WaitUntilCommand {
106-
robot.outtake.slides.position > Slides.min + (Slides.highBasket - Slides.min) / 2
109+
robot.outtake.slides.position > Slides.min + (Slides.highBasket - Slides.min) * 3 / 4
107110
}.andThen(
108111
robot.drive.pid(Pose2d(basketX, basketY, -45.0)),
109112
),
@@ -178,7 +181,7 @@ class SampleAuton : OpMode() {
178181
var sample1X = -47.0
179182

180183
@JvmField
181-
var sample1Y = 49.5
184+
var sample1Y = 50.0
182185

183186
@JvmField
184187
var sample2X = -47.0
@@ -209,6 +212,9 @@ class SampleAuton : OpMode() {
209212

210213
@JvmField
211214
var pidStablize: Long = 500
215+
216+
@JvmField
217+
var timeOutCVDelay: Long = 2000
212218
}
213219

214220
override fun exec() {
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
package org.firstinspires.ftc.teamcode.opmodes.auton
2+
3+
import com.acmerobotics.dashboard.config.Config
4+
import com.qualcomm.robotcore.eventloop.opmode.Autonomous
5+
6+
@Config
7+
@Autonomous(name = "Sample Auton Red", preselectTeleOp = "Main Teleop Red")
8+
class SampleAutonRed : SampleAuton() {
9+
override fun initialize() {
10+
robot.isRed = true
11+
super.initialize()
12+
}
13+
}

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmodes/auton/SpecimenAutonPush.kt‎

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -21,11 +21,11 @@ import org.firstinspires.ftc.teamcode.common.utils.OpMode
2121
import org.firstinspires.ftc.teamcode.common.utils.Pose2d
2222
import org.firstinspires.ftc.teamcode.common.utils.conditionalCommand
2323

24-
@Autonomous(name = "Specimen Auton Push", preselectTeleOp = "Main Teleop Red")
24+
@Autonomous(name = "Specimen Auton Push", preselectTeleOp = "Main Teleop Blue")
2525
// @TeleOp(name = "Specimen Auton", group = "Auton")
2626
@Config
2727
@SuppressWarnings("detekt:MagicNumber", "detekt:SpreadOperator")
28-
class SpecimenAutonPush : OpMode() {
28+
open class SpecimenAutonPush : OpMode() {
2929
override val robot by lazy { AutonRobot(this) }
3030

3131
val currentCommands = mutableListOf<String>()
@@ -183,10 +183,10 @@ class SpecimenAutonPush : OpMode() {
183183
return Path(
184184
listOf(
185185
pickupPos,
186-
Vec2d(-48.0, pickupPos.y),
186+
Vec2d(-50.0, pickupPos.y),
187187
) +
188188
listOf(
189-
Vec2d(-48, scoringPos.y) + offset,
189+
Vec2d(-54, scoringPos.y) + offset,
190190
scoringPos + offset,
191191
Vec2d(-36, scoringPos.y) + offset,
192192
) +
Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
package org.firstinspires.ftc.teamcode.opmodes.auton
2+
3+
import com.acmerobotics.dashboard.config.Config
4+
import com.qualcomm.robotcore.eventloop.opmode.Autonomous
5+
6+
@Config
7+
@Autonomous(name = "Specimen Auton Push Red", preselectTeleOp = "Main Teleop Red")
8+
class SpecimenAutonPushRed : SpecimenAutonPush() {
9+
override fun initialize() {
10+
robot.isRed = true
11+
super.initialize()
12+
}
13+
}

‎TeamCode/src/main/java/org/firstinspires/ftc/teamcode/opmodes/teleop/MainTeleop.kt‎

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -79,7 +79,7 @@ open class MainTeleopBlue : OpMode() {
7979
val liftResets =
8080
EdgeDetector(
8181
gp2::circle,
82-
outtake.slides.direct(Slides.rezeroPower),
82+
outtake.slides.goTo(Slides.State.REZERO),
8383
SequentialCommandGroup(
8484
outtake.slides.rezeroCmd(),
8585
outtake.slides.goTo(Slides.State.BASE),
@@ -479,7 +479,7 @@ open class MainTeleopBlue : OpMode() {
479479
var intakePickupClawDelay: Long = 250
480480

481481
@JvmField
482-
var baseIntakeDuration: Long = 1000
482+
var baseIntakeDuration: Long = 1250
483483

484484
@JvmField
485485
var intakeDuration: Long = 1000

0 commit comments

Comments
 (0)