mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[wpilib] Deprecate getInstance() in favor of static functions (#3440)
Co-authored-by: Noam Zaks <imnoamzaks@gmail.com>
This commit is contained in:
@@ -28,14 +28,14 @@ public class Robot extends TimedRobot {
|
||||
new Thread(
|
||||
() -> {
|
||||
// Get the Axis camera from CameraServer
|
||||
AxisCamera camera = CameraServer.getInstance().addAxisCamera("axis-camera.local");
|
||||
AxisCamera camera = CameraServer.addAxisCamera("axis-camera.local");
|
||||
// Set the resolution
|
||||
camera.setResolution(640, 480);
|
||||
|
||||
// Get a CvSink. This will capture Mats from the camera
|
||||
CvSink cvSink = CameraServer.getInstance().getVideo();
|
||||
CvSink cvSink = CameraServer.getVideo();
|
||||
// Setup a CvSource. This will send images back to the Dashboard
|
||||
CvSource outputStream = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
|
||||
CvSource outputStream = CameraServer.putVideo("Rectangle", 640, 480);
|
||||
|
||||
// Mats are very memory expensive. Lets reuse this Mat.
|
||||
Mat mat = new Mat();
|
||||
|
||||
@@ -28,14 +28,14 @@ public class Robot extends TimedRobot {
|
||||
new Thread(
|
||||
() -> {
|
||||
// Get the UsbCamera from CameraServer
|
||||
UsbCamera camera = CameraServer.getInstance().startAutomaticCapture();
|
||||
UsbCamera camera = CameraServer.startAutomaticCapture();
|
||||
// Set the resolution
|
||||
camera.setResolution(640, 480);
|
||||
|
||||
// Get a CvSink. This will capture Mats from the camera
|
||||
CvSink cvSink = CameraServer.getInstance().getVideo();
|
||||
CvSink cvSink = CameraServer.getVideo();
|
||||
// Setup a CvSource. This will send images back to the Dashboard
|
||||
CvSource outputStream = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
|
||||
CvSource outputStream = CameraServer.putVideo("Rectangle", 640, 480);
|
||||
|
||||
// Mats are very memory expensive. Lets reuse this Mat.
|
||||
Mat mat = new Mat();
|
||||
|
||||
@@ -15,6 +15,6 @@ import edu.wpi.first.wpilibj.TimedRobot;
|
||||
public class Robot extends TimedRobot {
|
||||
@Override
|
||||
public void robotInit() {
|
||||
CameraServer.getInstance().startAutomaticCapture();
|
||||
CameraServer.startAutomaticCapture();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
package edu.wpi.first.wpilibj.templates.educational;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
|
||||
/** Educational robot base class. */
|
||||
@@ -38,32 +39,32 @@ public class EducationalRobot extends RobotBase {
|
||||
|
||||
while (!Thread.currentThread().isInterrupted() && !m_exit) {
|
||||
if (isDisabled()) {
|
||||
m_ds.InDisabled(true);
|
||||
DriverStation.InDisabled(true);
|
||||
disabled();
|
||||
m_ds.InDisabled(false);
|
||||
DriverStation.InDisabled(false);
|
||||
while (isDisabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
} else if (isAutonomous()) {
|
||||
m_ds.InAutonomous(true);
|
||||
DriverStation.InAutonomous(true);
|
||||
autonomous();
|
||||
m_ds.InAutonomous(false);
|
||||
DriverStation.InAutonomous(false);
|
||||
while (isAutonomousEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
} else if (isTest()) {
|
||||
m_ds.InTest(true);
|
||||
DriverStation.InTest(true);
|
||||
test();
|
||||
m_ds.InTest(false);
|
||||
DriverStation.InTest(false);
|
||||
while (isTest() && isEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
} else {
|
||||
m_ds.InOperatorControl(true);
|
||||
DriverStation.InOperatorControl(true);
|
||||
teleop();
|
||||
m_ds.InOperatorControl(false);
|
||||
DriverStation.InOperatorControl(false);
|
||||
while (isOperatorControlEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,6 +5,7 @@
|
||||
package edu.wpi.first.wpilibj.templates.robotbaseskeleton;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.RobotBase;
|
||||
import edu.wpi.first.wpilibj.livewindow.LiveWindow;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
@@ -35,36 +36,36 @@ public class Robot extends RobotBase {
|
||||
|
||||
while (!Thread.currentThread().isInterrupted() && !m_exit) {
|
||||
if (isDisabled()) {
|
||||
m_ds.InDisabled(true);
|
||||
DriverStation.InDisabled(true);
|
||||
disabled();
|
||||
m_ds.InDisabled(false);
|
||||
DriverStation.InDisabled(false);
|
||||
while (isDisabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
} else if (isAutonomous()) {
|
||||
m_ds.InAutonomous(true);
|
||||
DriverStation.InAutonomous(true);
|
||||
autonomous();
|
||||
m_ds.InAutonomous(false);
|
||||
DriverStation.InAutonomous(false);
|
||||
while (isAutonomousEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
} else if (isTest()) {
|
||||
LiveWindow.setEnabled(true);
|
||||
Shuffleboard.enableActuatorWidgets();
|
||||
m_ds.InTest(true);
|
||||
DriverStation.InTest(true);
|
||||
test();
|
||||
m_ds.InTest(false);
|
||||
DriverStation.InTest(false);
|
||||
while (isTest() && isEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
LiveWindow.setEnabled(false);
|
||||
Shuffleboard.disableActuatorWidgets();
|
||||
} else {
|
||||
m_ds.InOperatorControl(true);
|
||||
DriverStation.InOperatorControl(true);
|
||||
teleop();
|
||||
m_ds.InOperatorControl(false);
|
||||
DriverStation.InOperatorControl(false);
|
||||
while (isOperatorControlEnabled()) {
|
||||
m_ds.waitForData();
|
||||
DriverStation.waitForData();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user