This repository has been archived by the owner on Mar 18, 2023. It is now read-only.
/
Robot.java
216 lines (158 loc) · 6.5 KB
/
Robot.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
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
package org.usfirst.frc.team6184.robot;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.Joystick;
import edu.wpi.first.wpilibj.Spark;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.Compressor;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.CameraServer;
import edu.wpi.first.wpilibj.Talon;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.PWMTalonSRX;
import edu.wpi.first.wpilibj.AnalogGyro;
import edu.wpi.first.wpilibj.BuiltInAccelerometer;
import org.opencv.core.Mat;
import org.opencv.core.Rect;
import org.opencv.imgproc.Imgproc;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.first.wpilibj.CameraServer;
import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.vision.VisionRunner;
import edu.wpi.first.wpilibj.vision.VisionThread;
import org.opencv.imgproc.Imgproc;
import org.opencv.core.*;
import edu.wpi.cscore.CvSink;
import edu.wpi.cscore.CvSource;
import edu.wpi.cscore.UsbCamera;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.GenericHID.Hand;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj.Solenoid;
import java.util.ArrayList;
// import that doc
import org.usfirst.frc.team6184.robot.GripPipeline;
/**
* This is a demo program showing the use of the RobotDrive class, specifically
* it contains the code necessary to operate a robot with tank drive.
*/
public class Robot extends IterativeRobot {
private DifferentialDrive m_myRobot;
private Joystick m_rightStick;
public static GripPipeline Pipe = new GripPipeline();
DoubleSolenoid exampleDouble = new DoubleSolenoid(0, 7);
Solenoid Cam = new Solenoid(1);
//AnalogGyro gyro= new AnalogGyro(0);
Compressor c = new Compressor();
private XboxController xbox;
// BuiltInAccelerometer Built =new BuiltInAccelerometer();
Spark lift = new Spark(3);
DigitalInput topLimitSwitch = new DigitalInput(8);
PWMTalonSRX m_frontLeft = new PWMTalonSRX(1);
Talon m_rearLeft = new Talon(2);
DigitalInput botLimitSwitch = new DigitalInput(9);
Thread m_visionThread;
SpeedControllerGroup m_left = new SpeedControllerGroup(m_frontLeft, m_rearLeft);
private static final int IMG_WIDTH = 320;
private static final int IMG_HEIGHT = 240;
private VisionThread visionThread;
GripPipeline pipe = new GripPipeline();
private double centerX = 0.0;
private final Object imgLock = new Object();
@Override
public void robotInit() {
CvSource outputStream = CameraServer.getInstance().putVideo("Blur", 640, 480);
m_myRobot = new DifferentialDrive(m_left, new PWMTalonSRX(0));
m_rightStick = new Joystick(1);
xbox = new XboxController(0);
UsbCamera camera2 = CameraServer.getInstance().startAutomaticCapture();
camera2.setFPS(60);
camera2.setResolution(360, 360);
UsbCamera camera = CameraServer.getInstance().startAutomaticCapture();
camera.setExposureManual(20);
camera.setResolution(IMG_WIDTH, IMG_HEIGHT);
visionThread = new VisionThread(camera, new GripPipeline(), pipeline -> {
if (pipeline.filterContoursOutput().size()>=2) {
Rect r = Imgproc.boundingRect(pipeline.filterContoursOutput().get(0));
Rect r2 = Imgproc.boundingRect(pipeline.filterContoursOutput().get(1));
Mat output = pipeline.resizeImageOutput();
Imgproc.rectangle(output, new Point(r.x, r.y), new Point(r.x+r.width, r.y+r.height), new Scalar(255, 0, 0), 5);
Imgproc.rectangle(output, new Point(r2.x, r2.y), new Point(r2.x+r2.width, r2.y+r2.height), new Scalar(0, 255, 0), 5);
synchronized (imgLock) {
centerX = (r.x + r2.x +(r2.width / 2)+(r.width/2))/2;
}
Imgproc.circle (
output, //Matrix obj of the image
new Point(centerX, 50), //Center of the circle
5, //Radius
new Scalar(0, 0, 255), //Scalar object for color
10
);
outputStream.putFrame(output);
}
});
visionThread.start();
}
@Override
public void teleopPeriodic() {
c.setClosedLoopControl(false);
double centerX;
synchronized (imgLock) {
centerX = this.centerX;
}
double turn = centerX - (IMG_WIDTH / 2);
System.out.println(turn);
//double Accellx = Built.getX();
//double AccellY = Built.getY();
//double Gravity = Built.getZ();
//double angle = gyro.getRate();
// System.out.println(angle);
boolean clickedA = xbox.getAButton();
boolean clickedB = xbox.getBButton();
boolean clickedY = xbox.getYButton();
boolean clickedX = xbox.getXButton();
boolean clicked7 = xbox.getBButton();
Double driveSpeed = m_rightStick.getThrottle();
System.out.println(driveSpeed);
//System.out.println(Gravity);
//m_myRobot.arcadeDrive( m_rightStick.getY()* driveSpeed,m_rightStick.getTwist()*0.7);
m_myRobot.curvatureDrive(m_rightStick.getY()*driveSpeed,m_rightStick.getZ()*0.7,true);
if (clickedX) {
Cam.set(true);
}
else{Cam.set(false);}
if (clickedX && clickedB)
{m_myRobot.curvatureDrive(0.3, turn * 0.008,true);
}
else {m_myRobot.curvatureDrive(m_rightStick.getY()*driveSpeed,m_rightStick.getZ()*0.7,true);}
if (clickedY){
exampleDouble.set(DoubleSolenoid.Value.kForward);
}
else if (!clickedY && clickedA){
exampleDouble.set(DoubleSolenoid.Value.kReverse);
}
else {
exampleDouble.set(DoubleSolenoid.Value.kOff);
}
lift.set(xbox.getY(Hand.kRight));
System.out.println("teleop code?>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>. ");
}
public void autonomousInit() {
teleopInit();
}
public void autonomousPeriodic(){
System.out.println("I'm gonna run in autonomous................................................................");
teleopPeriodic();
}
@Override
public void disabledInit(){
}
}