Skip to content

Commit e398df0

Browse files
committed
11.27.21 11:28
1 parent cb51874 commit e398df0

2 files changed

Lines changed: 4 additions & 4 deletions

File tree

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/mecanumDriveRed.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -126,10 +126,10 @@ public void runOpMode() {
126126

127127
//TODO
128128

129-
int ticks = 0;
130-
ticks += -(int) gamepad2.left_stick_y * 2;
129+
//int ticks = 0;
130+
//ticks += -(int) gamepad2.left_stick_y * 2;
131131
arm1.setPower(1);
132-
arm1.setTargetPosition(ticks);
132+
arm1.setTargetPosition(60);
133133
arm1.setMode(DcMotor.RunMode.RUN_TO_POSITION);
134134

135135

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/teleop/mecanumFieldOriented.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -56,7 +56,7 @@ public class mecanumFieldOriented extends LinearOpMode {
5656
BNO055IMU imu = hardwareMap.get(BNO055IMU.class, "imu 1");
5757

5858
public void initIMU(HardwareMap hwm) {
59-
imu = hwm.get(BNO055IMU.class, "imu");
59+
imu = hwm.get(BNO055IMU.class, "imu 1");
6060
BNO055IMU.Parameters parameters1 = new BNO055IMU.Parameters();
6161
parameters1.angleUnit = BNO055IMU.AngleUnit.DEGREES;
6262
parameters1.accelUnit = BNO055IMU.AccelUnit.METERS_PERSEC_PERSEC;

0 commit comments

Comments
 (0)