This repository has been archived by the owner on Sep 14, 2022. It is now read-only.
-
Notifications
You must be signed in to change notification settings - Fork 1
/
BotConfig.java
111 lines (95 loc) · 4.04 KB
/
BotConfig.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
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
package org.firstinspires.ftc.teamcode;
import com.qualcomm.hardware.bosch.BNO055IMU;
import com.qualcomm.hardware.rev.RevColorSensorV3;
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;
import com.qualcomm.robotcore.util.ElapsedTime;
import org.firstinspires.ftc.robotcore.external.hardware.camera.WebcamName;
/**
* This is NOT an opmode.
*
* This class can be used to define all the specific hardware for a single robot.
*/
public class BotConfig
{
/* Public OpMode members. */
public DcMotor leftFront = null;
public DcMotor leftBack = null;
public DcMotor rightFront = null;
public DcMotor rightBack = null;
public DcMotor winchMotor = null;
public DcMotor abductor = null;
public Servo basket = null;
public WebcamName camera = null;
public int cameraMonitor;
public String cameraName = null;
public RevColorSensorV3 cSensor = null; // basket color sensor
public BNO055IMU BNimu = null;
public IMU imu;
/* local OpMode members. */
HardwareMap hwMap = null;
private ElapsedTime period = new ElapsedTime();
/* Constructor */
public BotConfig(){
}
/* Initialize standard Hardware interfaces */
public void init(HardwareMap ahwMap) {
// Save reference to Hardware map
hwMap = ahwMap;
// Define and Initialize Motors
leftFront = hwMap.get(DcMotor.class, "FrontLeft");
leftBack = hwMap.get(DcMotor.class, "BackLeft");
rightFront = hwMap.get(DcMotor.class, "FrontRight");
rightBack = hwMap.get(DcMotor.class, "BackRight");
winchMotor = hwMap.get(DcMotor.class, "WinchMotor");
abductor = hwMap.get(DcMotor.class, "abductor");
BNimu = hwMap.get(BNO055IMU.class, "imu");
imu = new IMU(BNimu);
leftFront.setDirection (DcMotor.Direction.FORWARD);
leftBack.setDirection (DcMotor.Direction.FORWARD);
rightFront.setDirection(DcMotor.Direction.REVERSE);
rightBack.setDirection (DcMotor.Direction.REVERSE);
winchMotor.setDirection(DcMotor.Direction.FORWARD);
abductor.setDirection(DcMotor.Direction.FORWARD);
// Set all motors to zero power
leftFront.setPower(0);
leftBack.setPower(0);
rightFront.setPower(0);
rightBack.setPower(0);
winchMotor.setPower(0);
abductor.setPower(0);
// Set all motors to run without encoders.
leftFront.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
leftBack.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rightFront.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
rightBack.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
abductor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
abductor.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
winchMotor.setTargetPosition(0);
winchMotor.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
winchMotor.setMode(DcMotor.RunMode.RUN_TO_POSITION);
winchMotor.setPower(0.2);
// Define and initialize ALL installed servos.
basket = hwMap.get(Servo.class, "basket");
// Define and initialize color sensor
cSensor = hwMap.get(RevColorSensorV3.class, "cSensor");
cSensor.initialize();
cSensor.enableLed(true);
// *********************************** CAMERA STUFF *************************************
/*
// Define and initialize camera.
cameraName = "webcam";
camera = hwMap.get(WebcamName.class, cameraName);
// Define and initialize camera monitor.
// TODO: Ensure this works
cameraMonitor = hwMap
.appContext
.getResources()
.getIdentifier("cameraMintorViewId", "id", hwMap.appContext.getPackageName());
*/
//set abductor defaults
// abductor.setPosition(0.5); //0.5 is stop for a continuous rotation servo
// basket.setPosition(0.81);
}
}