-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathAutoTWAHardwareConfiguration.java
92 lines (75 loc) · 3.63 KB
/
AutoTWAHardwareConfiguration.java
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
package org.firstinspires.ftc.teamcode.RobotCoreExtensions;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.hardware.bosch.JustLoggingAccelerationIntegrator;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotor;
import org.firstinspires.ftc.teamcode.Subsystems.GlyphGrabber;
import org.firstinspires.ftc.teamcode.Subsystems.GlyphLift;
import org.firstinspires.ftc.teamcode.Subsystems.GlyphSpinner;
import org.firstinspires.ftc.teamcode.Subsystems.JewelArm;
import org.firstinspires.ftc.teamcode.Subsystems.RelicArm;
import org.firstinspires.ftc.teamcode.Subsystems.RelicClaw;
import org.firstinspires.ftc.teamcode.Subsystems.RelicLift;
public class AutoTWAHardwareConfiguration
{
LinearOpMode opMode;
//Robot Components
public Drivetrain drivetrain;
public GlyphSpinner glyphSpinner;
public GlyphLift glyphLift;
public GlyphGrabber glyphGrabber;
public RelicLift relicLift;
public RelicArm relicArm;
public RelicClaw relicClaw;
public JewelArm jewelArm;
//Sensors
public BNO055IMU adafruitIMU;
//Auto Drivers
public GyroAutoDriver2017 gyroAutoDriver;
public EncoderAutoDriver2017 encoderAutoDriver;
public RangeAutoDriver rangeAutoDriver;
public OpticalDistanceAutoDriver opticalDistanceAutoDriver;
AutoTWAHardwareConfiguration(LinearOpMode opMode)
{
this.opMode = opMode;
//Define robot components
DcMotor left1 = opMode.hardwareMap.dcMotor.get("left1");
DcMotor left2 = opMode.hardwareMap.dcMotor.get("left2");
DcMotor right1 = opMode.hardwareMap.dcMotor.get("right1");
DcMotor right2 = opMode.hardwareMap.dcMotor.get("right2");
left1.setDirection(DcMotor.Direction.REVERSE);
left2.setDirection(DcMotor.Direction.REVERSE);
right1.setDirection(DcMotor.Direction.FORWARD);
right2.setDirection(DcMotor.Direction.FORWARD);
drivetrain = new Drivetrain.Builder()
.addLeftMotor(left1)
.addLeftMotorWithEncoder(left2)
.addRightMotor(right1)
.addRightMotorWithEncoder(right2)
.build();
glyphGrabber = new GlyphGrabber("leftservo1","leftservo2","rightservo1","rightservo2", opMode.hardwareMap);
glyphSpinner = new GlyphSpinner("spinner", "SpinnerTouch1", "SpinnerTouch2", opMode.hardwareMap);
glyphLift = new GlyphLift("GlyphLift", "LiftTouch", opMode.hardwareMap);
relicLift = new RelicLift("RelicLift", opMode.hardwareMap);
relicArm = new RelicArm("RelicArm", opMode.hardwareMap);
relicClaw = new RelicClaw("ClawServo1","ClawServo2", "Pivot", opMode.hardwareMap);
jewelArm = new JewelArm("JewelArm", "JewelColor", opMode.hardwareMap);
//Define sensors
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
parameters.angleUnit = BNO055IMU.AngleUnit.DEGREES;
parameters.accelUnit = BNO055IMU.AccelUnit.METERS_PERSEC_PERSEC;
parameters.calibrationDataFile = "BNO055IMUCalibration.json"; // see the calibration sample opmode
parameters.loggingEnabled = true;
parameters.loggingTag = "IMU";
parameters.accelerationIntegrationAlgorithm = new JustLoggingAccelerationIntegrator();
adafruitIMU = opMode.hardwareMap.get(BNO055IMU.class, "imu 1");
adafruitIMU.initialize(parameters);
//Define auto drivers
gyroAutoDriver = new GyroAutoDriver2017(this);
encoderAutoDriver = new EncoderAutoDriver2017(this);
}
void init()
{
// :) oh happy day, there is nothing here. :)
}
}