[examples] Prepare for RobotInit deprecation by updating examples (#6623)

Co-authored-by: Tyler Veness <calcmogul@gmail.com>
This commit is contained in:
Jade
2024-07-17 11:22:39 +08:00
committed by GitHub
parent f62a055608
commit 57fa388724
156 changed files with 260 additions and 355 deletions

View File

@@ -15,8 +15,8 @@ import edu.wpi.first.wpilibj.LEDPattern;
import edu.wpi.first.wpilibj.TimedRobot;
public class Robot extends TimedRobot {
private AddressableLED m_led;
private AddressableLEDBuffer m_ledBuffer;
private final AddressableLED m_led;
private final AddressableLEDBuffer m_ledBuffer;
// Create an LED pattern that will display a rainbow across
// all hues at maximum saturation and half brightness
@@ -30,8 +30,8 @@ public class Robot extends TimedRobot {
private final LEDPattern m_scrollingRainbow =
m_rainbow.scrollAtAbsoluteSpeed(MetersPerSecond.of(1), kLedSpacing);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
// PWM port 9
// Must be a PWM header, not MXP or DIO
m_led = new AddressableLED(9);

View File

@@ -30,8 +30,8 @@ import org.opencv.imgproc.Imgproc;
* <p>Be aware that the performance on this is much worse than a coprocessor solution!
*/
public class Robot extends TimedRobot {
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
var visionThread = new Thread(this::apriltagVisionThreadProc);
visionThread.setDaemon(true);
visionThread.start();

View File

@@ -21,13 +21,11 @@ public class Robot extends TimedRobot {
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final Joystick m_stick = new Joystick(0);
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override
public void robotInit() {
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -21,13 +21,11 @@ public class Robot extends TimedRobot {
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final XboxController m_driverController = new XboxController(0);
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override
public void robotInit() {
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -13,8 +13,7 @@ public class Robot extends TimedRobot {
private final Arm m_arm = new Arm();
private final Joystick m_joystick = new Joystick(Constants.kJoystickPort);
@Override
public void robotInit() {}
public Robot() {}
@Override
public void simulationPeriodic() {

View File

@@ -15,8 +15,7 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class Robot extends TimedRobot {
private final PowerDistribution m_pdp = new PowerDistribution();
@Override
public void robotInit() {
public Robot() {
// Put the PDP itself to the dashboard
SmartDashboard.putData("PDP", m_pdp);
}

View File

@@ -15,22 +15,22 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/** This is a sample program showing how to to use DMA to read a sensor. */
public class Robot extends TimedRobot {
private DMA m_dma;
private DMASample m_dmaSample;
private final DMA m_dma;
private final DMASample m_dmaSample;
// DMA needs a trigger, can use an output as trigger.
// 8 Triggers exist per DMA object, can be triggered on any
// DigitalSource.
private DigitalOutput m_dmaTrigger;
private final DigitalOutput m_dmaTrigger;
// Analog input to read with DMA
private AnalogInput m_analogInput;
private final AnalogInput m_analogInput;
// Encoder to read with DMA
private Encoder m_encoder;
private final Encoder m_encoder;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_dma = new DMA();
m_dmaSample = new DMASample();
m_dmaTrigger = new DigitalOutput(2);

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -11,12 +11,12 @@ import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
/** This example shows how to use a duty cycle encoder for devices such as an arm or elevator. */
public class Robot extends TimedRobot {
private DutyCycleEncoder m_dutyCycleEncoder;
private final DutyCycleEncoder m_dutyCycleEncoder;
private static final double m_fullRange = 1.3;
private static final double m_expectedZero = 0;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
// 2nd parameter is the range of values. This sensor will output between
// 0 and the passed in value.
// 3rd parameter is the the physical value where you want "0" to be. How

View File

@@ -10,10 +10,9 @@ import edu.wpi.first.wpilibj.TimedRobot;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
public class Robot extends TimedRobot {
private DutyCycle m_dutyCycle;
private final DutyCycle m_dutyCycle;
@Override
public void robotInit() {
public Robot() {
m_dutyCycle = new DutyCycle(new DigitalInput(0));
}

View File

@@ -27,8 +27,7 @@ public class Robot extends TimedRobot {
private ExponentialProfile.State m_goal = new ExponentialProfile.State(0, 0);
private ExponentialProfile.State m_setpoint = new ExponentialProfile.State(0, 0);
@Override
public void robotInit() {
public Robot() {
// Note: These gains are fake, and will have to be tuned for your robot.
m_motor.setPID(1.3, 0.0, 0.7);
}

View File

@@ -17,9 +17,6 @@ public class Robot extends TimedRobot {
super(0.020);
}
@Override
public void robotInit() {}
@Override
public void robotPeriodic() {
// Update the telemetry, including mechanism visualization, regardless of mode.

View File

@@ -36,8 +36,7 @@ public class Robot extends TimedRobot {
new ProfiledPIDController(kP, kI, kD, m_constraints, kDt);
private final ElevatorFeedforward m_feedforward = new ElevatorFeedforward(kS, kG, kV);
@Override
public void robotInit() {
public Robot() {
m_encoder.setDistancePerPulse(1.0 / 360.0 * 2.0 * Math.PI * 1.5);
}

View File

@@ -13,8 +13,7 @@ public class Robot extends TimedRobot {
private final Joystick m_joystick = new Joystick(Constants.kJoystickPort);
private final Elevator m_elevator = new Elevator();
@Override
public void robotInit() {}
public Robot() {}
@Override
public void robotPeriodic() {

View File

@@ -27,8 +27,7 @@ public class Robot extends TimedRobot {
private TrapezoidProfile.State m_goal = new TrapezoidProfile.State();
private TrapezoidProfile.State m_setpoint = new TrapezoidProfile.State();
@Override
public void robotInit() {
public Robot() {
// Note: These gains are fake, and will have to be tuned for your robot.
m_motor.setPID(1.3, 0.0, 0.7);
}

View File

@@ -34,8 +34,8 @@ public class Robot extends TimedRobot {
*/
private final Encoder m_encoder = new Encoder(1, 2, false, CounterBase.EncodingType.k4X);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
/*
* Defines the number of samples to average when determining the rate.
* On a quadrature encoder, values range from 1-255;

View File

@@ -35,8 +35,8 @@ public class Robot extends TimedRobot {
private final EventLoop m_loop = new EventLoop();
private final Joystick m_joystick = new Joystick(0);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_controller.setTolerance(TOLERANCE);
BooleanEvent isBallAtKicker =

View File

@@ -68,8 +68,7 @@ public class Robot extends TimedRobot {
private final FlywheelSim m_flywheelSim = new FlywheelSim(m_plant, m_gearbox);
private final EncoderSim m_encoderSim = new EncoderSim(m_encoder);
@Override
public void robotInit() {
public Robot() {
// Add bang-bang controler to SmartDashboard and networktables.
SmartDashboard.putData(m_bangBangControler);
}

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -25,17 +25,11 @@ public class Robot extends TimedRobot {
private final XboxController m_controller = new XboxController(0);
private final Timer m_timer = new Timer();
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
}
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.

View File

@@ -36,13 +36,11 @@ public class Robot extends TimedRobot {
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
private final Joystick m_joystick = new Joystick(kJoystickPort);
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftDrive);
SendableRegistry.addChild(m_robotDrive, m_rightDrive);
}
@Override
public void robotInit() {
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -27,22 +27,17 @@ public class Robot extends TimedRobot {
private static final int kGyroPort = 0;
private static final int kJoystickPort = 0;
private MecanumDrive m_robotDrive;
private final MecanumDrive m_robotDrive;
private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
private final Joystick m_joystick = new Joystick(kJoystickPort);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
PWMSparkMax frontLeft = new PWMSparkMax(kFrontLeftChannel);
PWMSparkMax rearLeft = new PWMSparkMax(kRearLeftChannel);
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
// Invert the right side motors.
// You may need to change or remove this to match your robot.
frontRight.setInverted(true);
@@ -51,6 +46,11 @@ public class Robot extends TimedRobot {
m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set);
m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
}
/** Mecanum drive is used with the gyro angle as an input. */

View File

@@ -19,14 +19,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -19,14 +19,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -22,8 +22,8 @@ import org.opencv.imgproc.Imgproc;
public class Robot extends TimedRobot {
Thread m_visionThread;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_visionThread =
new Thread(
() -> {

View File

@@ -22,8 +22,8 @@ import org.opencv.imgproc.Imgproc;
public class Robot extends TimedRobot {
Thread m_visionThread;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_visionThread =
new Thread(
() -> {

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -19,21 +19,16 @@ public class Robot extends TimedRobot {
private static final int kJoystickChannel = 0;
private MecanumDrive m_robotDrive;
private Joystick m_stick;
private final MecanumDrive m_robotDrive;
private final Joystick m_stick;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
PWMSparkMax frontLeft = new PWMSparkMax(kFrontLeftChannel);
PWMSparkMax rearLeft = new PWMSparkMax(kRearLeftChannel);
PWMSparkMax frontRight = new PWMSparkMax(kFrontRightChannel);
PWMSparkMax rearRight = new PWMSparkMax(kRearRightChannel);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
// Invert the right side motors.
// You may need to change or remove this to match your robot.
frontRight.setInverted(true);
@@ -42,6 +37,11 @@ public class Robot extends TimedRobot {
m_robotDrive = new MecanumDrive(frontLeft::set, rearLeft::set, frontRight::set, rearRight::set);
m_stick = new Joystick(kJoystickChannel);
SendableRegistry.addChild(m_robotDrive, frontLeft);
SendableRegistry.addChild(m_robotDrive, rearLeft);
SendableRegistry.addChild(m_robotDrive, frontRight);
SendableRegistry.addChild(m_robotDrive, rearRight);
}
@Override

View File

@@ -33,11 +33,11 @@ public class Robot extends TimedRobot {
private final Encoder m_elevatorEncoder = new Encoder(0, 1);
private final Joystick m_joystick = new Joystick(0);
private MechanismLigament2d m_elevator;
private MechanismLigament2d m_wrist;
private final MechanismLigament2d m_elevator;
private final MechanismLigament2d m_wrist;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_elevatorEncoder.setDistancePerPulse(kMetersPerPulse);
// the main mechanism object

View File

@@ -26,12 +26,12 @@ public class Robot extends TimedRobot {
private static final int kEncoderPortA = 0;
private static final int kEncoderPortB = 1;
private PWMSparkMax m_motor;
private Joystick m_joystick;
private Encoder m_encoder;
private final PWMSparkMax m_motor;
private final Joystick m_joystick;
private final Encoder m_encoder;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_motor = new PWMSparkMax(kMotorPort);
m_joystick = new Joystick(kJoystickPort);
m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
@@ -49,6 +49,7 @@ public class Robot extends TimedRobot {
SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
}
/** The teleop periodic function is called every control packet in teleop. */
@Override
public void teleopPeriodic() {
m_motor.set(m_joystick.getY());

View File

@@ -10,11 +10,10 @@ import edu.wpi.first.wpilibj.TimedRobot;
/**
* Uses the CameraServer class to automatically capture video from a USB webcam and send it to the
* FRC dashboard without doing any vision processing. This is the easiest way to get camera images
* to the dashboard. Just add this to the robotInit() method in your program.
* to the dashboard. Just add this to the robot class constructor.
*/
public class Robot extends TimedRobot {
@Override
public void robotInit() {
public Robot() {
CameraServer.startAutomaticCapture();
}
}

View File

@@ -42,7 +42,7 @@ public class RapidReactCommandBot {
* Use this method to define bindings between conditions and commands. These are useful for
* automating robot behaviors based on button and sensor input.
*
* <p>Should be called during {@link Robot#robotInit()}.
* <p>Should be called in the robot class constructor.
*
* <p>Event binding methods are available on the {@link Trigger} class.
*/

View File

@@ -27,8 +27,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Configure default commands and condition bindings on robot startup
m_robot.configureBindings();

View File

@@ -16,14 +16,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
*/
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -26,10 +26,10 @@ public class Robot extends TimedRobot {
private final PWMSparkMax m_elevatorMotor = new PWMSparkMax(2);
private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0);
private GenericEntry m_maxSpeed;
private final GenericEntry m_maxSpeed;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_tankDrive, m_leftDriveMotor);
SendableRegistry.addChild(m_tankDrive, m_rightDriveMotor);

View File

@@ -28,10 +28,10 @@ public class Robot extends TimedRobot {
private final Drivetrain m_drive = new Drivetrain();
private final LTVUnicycleController m_feedback = new LTVUnicycleController(0.020);
private final Timer m_timer = new Timer();
private Trajectory m_trajectory;
private final Trajectory m_trajectory;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
m_trajectory =
TrajectoryGenerator.generateTrajectory(
new Pose2d(2, 2, Rotation2d.kZero),

View File

@@ -44,8 +44,8 @@ public class Robot extends TimedRobot {
static final int kDoubleSolenoidReverseButton = 3;
static final int kCompressorButton = 4;
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
// Publish elements to shuffleboard.
ShuffleboardTab tab = Shuffleboard.getTab("Pneumatics");
tab.add("Single Solenoid", m_solenoid);

View File

@@ -101,8 +101,7 @@ public class Robot extends TimedRobot {
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);
@Override
public void robotInit() {
public Robot() {
// We go 2 pi radians in 1 rotation, or 4096 counts.
m_encoder.setDistancePerPulse(Math.PI * 2 / 4096.0);
}

View File

@@ -109,8 +109,7 @@ public class Robot extends TimedRobot {
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);
@Override
public void robotInit() {
public Robot() {
// Circumference = pi * d, so distance per click = pi * d / counts
m_encoder.setDistancePerPulse(Math.PI * 2 * kDrumRadius / 4096.0);
}

View File

@@ -81,8 +81,7 @@ public class Robot extends TimedRobot {
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);
@Override
public void robotInit() {
public Robot() {
// We go 2 pi radians per 4096 clicks.
m_encoder.setDistancePerPulse(2.0 * Math.PI / 4096.0);
}

View File

@@ -76,8 +76,7 @@ public class Robot extends TimedRobot {
// A joystick to read the trigger from.
private final Joystick m_joystick = new Joystick(kJoystickPort);
@Override
public void robotInit() {
public Robot() {
// We go 2 pi radians per 4096 clicks.
m_encoder.setDistancePerPulse(2.0 * Math.PI / 4096.0);
}

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -23,8 +23,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Configure default commands and condition bindings on robot startup
m_robot.configureBindings();
}

View File

@@ -31,7 +31,7 @@ public class SysIdRoutineBot {
* Use this method to define bindings between conditions and commands. These are useful for
* automating robot behaviors based on button and sensor input.
*
* <p>Should be called during {@link Robot#robotInit()}.
* <p>Should be called in the robot class constructor.
*
* <p>Event binding methods are available on the {@link Trigger} class.
*/

View File

@@ -15,18 +15,15 @@ import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
* the code necessary to operate a robot with tank drive.
*/
public class Robot extends TimedRobot {
private DifferentialDrive m_robotDrive;
private Joystick m_leftStick;
private Joystick m_rightStick;
private final DifferentialDrive m_robotDrive;
private final Joystick m_leftStick;
private final Joystick m_rightStick;
private final PWMSparkMax m_leftMotor = new PWMSparkMax(0);
private final PWMSparkMax m_rightMotor = new PWMSparkMax(1);
@Override
public void robotInit() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
/** Called once at the beginning of the robot program. */
public Robot() {
// We need to invert one side of the drivetrain so that positive voltages
// result in both sides moving forward. Depending on how your robot's
// gearbox is constructed, you might have to invert the left side instead.
@@ -35,6 +32,9 @@ public class Robot extends TimedRobot {
m_robotDrive = new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
m_leftStick = new Joystick(0);
m_rightStick = new Joystick(1);
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);
}
@Override

View File

@@ -21,8 +21,8 @@ public class Robot extends TimedRobot {
new DifferentialDrive(m_leftMotor::set, m_rightMotor::set);
private final XboxController m_driverController = new XboxController(0);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
SendableRegistry.addChild(m_robotDrive, m_leftMotor);
SendableRegistry.addChild(m_robotDrive, m_rightMotor);

View File

@@ -17,8 +17,8 @@ public class Robot extends TimedRobot {
// Creates a ping-response Ultrasonic object on DIO 1 and 2.
Ultrasonic m_rangeFinder = new Ultrasonic(1, 2);
@Override
public void robotInit() {
/** Called once at the beginning of the robot program. */
public Robot() {
// Add the ultrasonic on the "Sensors" tab of the dashboard
// Data will update automatically
Shuffleboard.getTab("Sensors").add(m_rangeFinder);

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -11,10 +11,9 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
@Override
public void robotInit() {
public Robot() {
m_robotContainer = new RobotContainer();
}

View File

@@ -12,7 +12,7 @@ import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
/** Educational robot base class. */
public class EducationalRobot extends RobotBase {
public void robotInit() {}
public EducationalRobot() {}
public void disabled() {}
@@ -34,8 +34,6 @@ public class EducationalRobot extends RobotBase {
@Override
public void startCompetition() {
robotInit();
DriverStationModeThread modeThread = new DriverStationModeThread();
int event = WPIUtilJNI.createEvent(false, false);

View File

@@ -14,8 +14,7 @@ public class Robot extends EducationalRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {}
public Robot() {}
/** This function is run when the robot is enabled. */
@Override

View File

@@ -15,7 +15,7 @@ import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
* package after creating this project, you must also update the build.gradle file in the project.
*/
public class Robot extends RobotBase {
public void robotInit() {}
public Robot() {}
public void disabled() {}
@@ -29,8 +29,6 @@ public class Robot extends RobotBase {
@Override
public void startCompetition() {
robotInit();
DriverStationModeThread modeThread = new DriverStationModeThread();
int event = WPIUtilJNI.createEvent(false, false);

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -12,7 +12,7 @@ import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
/** Educational robot base class. */
public class EducationalRobot extends RobotBase {
public void robotInit() {}
public EducationalRobot() {}
public void disabled() {}
@@ -34,8 +34,6 @@ public class EducationalRobot extends RobotBase {
@Override
public void startCompetition() {
robotInit();
DriverStationModeThread modeThread = new DriverStationModeThread();
int event = WPIUtilJNI.createEvent(false, false);

View File

@@ -14,8 +14,7 @@ public class Robot extends EducationalRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {}
public Robot() {}
/** This function is run when the robot is enabled. */
@Override

View File

@@ -26,8 +26,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto choices", m_chooser);

View File

@@ -24,8 +24,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto choices", m_chooser);

View File

@@ -17,8 +17,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {}
public Robot() {}
@Override
public void robotPeriodic() {}

View File

@@ -38,14 +38,7 @@ public class Robot extends TimesliceRobot {
// Total usage: 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2)
// = 9 ms -> 90% allocated
}
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto choices", m_chooser);

View File

@@ -34,13 +34,6 @@ public class Robot extends TimesliceRobot {
// 9 ms / 10 ms -> 90% allocated
}
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {}
@Override
public void robotPeriodic() {}

View File

@@ -17,14 +17,13 @@ import edu.wpi.first.wpilibj2.command.CommandScheduler;
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
private final RobotContainer m_robotContainer;
/**
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
// Instantiate our RobotContainer. This will perform all our button bindings, and put our
// autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();

View File

@@ -12,7 +12,7 @@ import edu.wpi.first.wpilibj.internal.DriverStationModeThread;
/** Educational robot base class. */
public class EducationalRobot extends RobotBase {
public void robotInit() {}
public EducationalRobot() {}
public void disabled() {}
@@ -34,8 +34,6 @@ public class EducationalRobot extends RobotBase {
@Override
public void startCompetition() {
robotInit();
DriverStationModeThread modeThread = new DriverStationModeThread();
int event = WPIUtilJNI.createEvent(false, false);

View File

@@ -14,8 +14,7 @@ public class Robot extends EducationalRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {}
public Robot() {}
/** This function is run when the robot is enabled. */
@Override

View File

@@ -26,8 +26,7 @@ public class Robot extends TimedRobot {
* This function is run when the robot is first started up and should be used for any
* initialization code.
*/
@Override
public void robotInit() {
public Robot() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto choices", m_chooser);