@@ -53,16 +53,7 @@ public class mecanumFieldOriented extends LinearOpMode {
5353 public static Orientation angles ;
5454 public static Acceleration gravity ;
5555
56- // Declare OpMode members.
57- DcMotor lF = hardwareMap .dcMotor .get ("front_left" );
58- DcMotor lB = hardwareMap .dcMotor .get ("back_left" );
59- DcMotor rF = hardwareMap .dcMotor .get ("front_right" );
60- DcMotor rB = hardwareMap .dcMotor .get ("back_right" );
61- DcMotor arm1 = hardwareMap .dcMotor .get ("arm1" );
62- DcMotor duckies = hardwareMap .dcMotor .get ("duckies" );
63- Servo wrist1 = hardwareMap .servo .get ("wrist" );
64- Servo grabber = hardwareMap .servo .get ("grabber" );
65- BNO055IMU imu = hardwareMap .get (BNO055IMU .class , "imu" );
56+ BNO055IMU imu = hardwareMap .get (BNO055IMU .class , "imu 1" );
6657
6758 public void initIMU (HardwareMap hwm ) {
6859 imu = hwm .get (BNO055IMU .class , "imu" );
@@ -80,6 +71,19 @@ public void initIMU(HardwareMap hwm) {
8071
8172 @ Override
8273 public void runOpMode () {
74+
75+ // Declare OpMode members.
76+ DcMotor lF = hardwareMap .dcMotor .get ("front_left" );
77+ DcMotor lB = hardwareMap .dcMotor .get ("back_left" );
78+ DcMotor rF = hardwareMap .dcMotor .get ("front_right" );
79+ DcMotor rB = hardwareMap .dcMotor .get ("back_right" );
80+ DcMotor arm1 = hardwareMap .dcMotor .get ("arm1" );
81+ DcMotor duckies = hardwareMap .dcMotor .get ("duckies" );
82+ Servo wrist1 = hardwareMap .servo .get ("wrist" );
83+ Servo grabber = hardwareMap .servo .get ("grabber" );
84+
85+
86+
8387 initIMU (hardwareMap );
8488 telemetry .addData ("Status" , "Initialized" );
8589 telemetry .update ();
@@ -109,7 +113,6 @@ public void runOpMode() {
109113 double frontRightPower ;
110114 double backLeftPower ;
111115 double backRightPower ;
112- double duckiesPower ;
113116
114117
115118 //set gamepad values
0 commit comments