@@ -53,10 +53,10 @@ public class mecanumFieldOriented extends LinearOpMode {
5353 public static Orientation angles ;
5454 public static Acceleration gravity ;
5555
56- // BNO055IMU imu = hardwareMap.get(BNO055IMU.class, "imu 1") ;
57- /*
56+ BNO055IMU imu ;
57+
5858 public void initIMU (HardwareMap hwm ) {
59- imu = hwm.get(BNO055IMU.class, "imu 1 ");
59+ imu = hwm .get (BNO055IMU .class , "imu" );
6060 BNO055IMU .Parameters parameters1 = new BNO055IMU .Parameters ();
6161 parameters1 .angleUnit = BNO055IMU .AngleUnit .DEGREES ;
6262 parameters1 .accelUnit = BNO055IMU .AccelUnit .METERS_PERSEC_PERSEC ;
@@ -68,7 +68,7 @@ public void initIMU(HardwareMap hwm) {
6868
6969 angles = imu .getAngularOrientation (AxesReference .INTRINSIC , AxesOrder .ZYX , AngleUnit .DEGREES );
7070 }
71- */
71+
7272 @ Override
7373 public void runOpMode () {
7474
@@ -81,10 +81,11 @@ public void runOpMode() {
8181 DcMotor duckies = hardwareMap .dcMotor .get ("duckies" );
8282 Servo wrist1 = hardwareMap .servo .get ("wrist" );
8383 Servo grabber = hardwareMap .servo .get ("grabber" );
84+ BNO055IMU imu = hardwareMap .get (BNO055IMU .class , "imu" );
8485
8586
8687
87- // initIMU(hardwareMap);
88+ initIMU (hardwareMap );
8889 telemetry .addData ("Status" , "Initialized" );
8990 telemetry .update ();
9091
@@ -191,7 +192,6 @@ public void runOpMode() {
191192 //set arm positions
192193 int ticks = 0 ;
193194 ticks += -(int ) gamepad2 .left_stick_y * 2 ;
194- arm1 .setPower (1 );
195195 arm1 .setTargetPosition (ticks );
196196 arm1 .setMode (DcMotor .RunMode .RUN_TO_POSITION );
197197
0 commit comments