[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

@@ -30,6 +30,12 @@
* private double angleToTote = 0;
* private double distanceToTote = 0;
*
* public Robot() {
* usbCamera = CameraServer.startAutomaticCapture(0);
* findTotePipeline = new MyFindTotePipeline();
* findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
* }
*
* {@literal @}Override
* public void {@link edu.wpi.first.vision.VisionRunner.Listener#copyPipelineOutputs
* copyPipelineOutputs(MyFindTotePipeline pipeline)} {
@@ -43,13 +49,6 @@
* }
*
* {@literal @}Override
* public void robotInit() {
* usbCamera = CameraServer.startAutomaticCapture(0);
* findTotePipeline = new MyFindTotePipeline();
* findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
* }
*
* {@literal @}Override
* public void autonomousInit() {
* findToteThread.start();
* }

View File

@@ -11,8 +11,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() {}
/** This function is run once each time the robot enters autonomous mode. */
@Override

View File

@@ -5,11 +5,12 @@
#include <frc/TimedRobot.h>
class Robot : public frc::TimedRobot {
public:
/**
* This function is run when the robot is first started up and should be
* used for any initialization code.
*/
void RobotInit() override {}
Robot() {}
/**
* This function is run once each time the robot enters autonomous mode

View File

@@ -63,10 +63,8 @@ class IterativeRobotBase : public RobotBase {
* which will be called when the robot is first powered on. It will be called
* exactly one time.
*
* Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
* indicators will be off until RobotInit() exits. Code in RobotInit() that
* waits for enable will cause the robot to never indicate that the code is
* ready, causing the robot to be bypassed in a match.
* Note: This method is functionally identical to the class constructor so
* that should be used instead.
*/
virtual void RobotInit();

View File

@@ -48,9 +48,7 @@ class MockRobot : public TimedRobot {
std::atomic<uint32_t> m_teleopPeriodicCount{0};
std::atomic<uint32_t> m_testPeriodicCount{0};
MockRobot() : TimedRobot{kPeriod} {}
void RobotInit() override { m_robotInitCount++; }
MockRobot() : TimedRobot{kPeriod} { m_robotInitCount++; }
void SimulationInit() override { m_simulationInitCount++; }

View File

@@ -4,7 +4,7 @@
#include "Robot.h"
void Robot::RobotInit() {
Robot::Robot() {
// Default to a length of 60, start empty output
// Length is expensive to set, so only set it once, then just update data
m_led.SetLength(kLength);

View File

@@ -12,7 +12,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
private:

View File

@@ -32,6 +32,19 @@
* solution!
*/
class Robot : public frc::TimedRobot {
public:
Robot() {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
#if defined(__linux__) || defined(_WIN32)
std::thread visionThread(VisionThread);
visionThread.detach();
#else
std::fputs("Vision only available on Linux or Windows.\n", stderr);
std::fflush(stderr);
#endif
}
#if defined(__linux__) || defined(_WIN32)
private:
@@ -147,18 +160,6 @@ class Robot : public frc::TimedRobot {
}
}
#endif
void RobotInit() override {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
#if defined(__linux__) || defined(_WIN32)
std::thread visionThread(VisionThread);
visionThread.detach();
#else
std::fputs("Vision only available on Linux or Windows.\n", stderr);
std::fflush(stderr);
#endif
}
};
#ifndef RUNNING_FRC_TESTS

View File

@@ -23,9 +23,7 @@ class Robot : public frc::TimedRobot {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
}
void RobotInit() override {
// 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

@@ -23,9 +23,7 @@ class Robot : public frc::TimedRobot {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
}
void RobotInit() override {
// 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

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -14,7 +14,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {}
Robot() {}
void SimulationPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;

View File

@@ -13,7 +13,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
// Put the PDP itself to the dashboard
frc::SmartDashboard::PutData("PDP", &m_pdp);
}

View File

@@ -25,7 +25,7 @@ class Robot : public frc::TimedRobot {
frc::Encoder m_encoder{0, 1};
public:
void RobotInit() override {
Robot() {
// Trigger on falling edge of dma trigger output
m_dma.SetExternalTrigger(&m_dmaTrigger, false, true);

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -20,7 +20,7 @@ class Robot : public frc::TimedRobot {
frc::DutyCycleEncoder m_dutyCycleEncoder{0, fullRange, expectedZero};
public:
void RobotInit() override {
Robot() {
// If you know the frequency of your sensor, uncomment the following
// method, and set the method to the frequency of your sensor.
// This will result in more stable readings from the sensor.

View File

@@ -12,7 +12,7 @@ class Robot : public frc::TimedRobot {
frc::DutyCycle m_dutyCycle{m_input}; // Duty cycle input
public:
void RobotInit() override {}
Robot() {}
void RobotPeriodic() override {
// Duty Cycle Frequency in Hz

View File

@@ -14,7 +14,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {}
Robot() {}
void RobotPeriodic() override;
void SimulationPeriodic() override;
void TeleopInit() override;

View File

@@ -14,7 +14,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {}
Robot() {}
void RobotPeriodic() override;
void SimulationPeriodic() override;
void TeleopPeriodic() override;

View File

@@ -22,7 +22,7 @@ static const auto KICKER_THRESHOLD = 15_mm;
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
m_controller.SetTolerance(TOLERANCE.value());
frc::BooleanEvent isBallAtKicker{&m_loop, [&kickerSensor = m_kickerSensor] {

View File

@@ -40,7 +40,7 @@ class Robot : public frc::TimedRobot {
0.9 * m_feedforward.Calculate(setpoint));
}
void RobotInit() override {
Robot() {
// Add bang-bang controler to SmartDashboard and networktables.
frc::SmartDashboard::PutData("BangBangControler", &m_bangBangControler);
}

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -18,16 +18,14 @@
class Robot : public frc::TimedRobot {
public:
Robot() {
wpi::SendableRegistry::AddChild(&m_drive, &m_left);
wpi::SendableRegistry::AddChild(&m_drive, &m_right);
}
void RobotInit() override {
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
// gearbox is constructed, you might have to invert the left side instead.
m_right.SetInverted(true);
wpi::SendableRegistry::AddChild(&m_drive, &m_left);
wpi::SendableRegistry::AddChild(&m_drive, &m_right);
}
/**

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -15,7 +15,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);

View File

@@ -9,7 +9,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {
Robot::Robot() {
// Start recording to data log
frc::DataLogManager::Start();

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -9,7 +9,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {
Robot::Robot() {
// Start recording to data log
frc::DataLogManager::Start();

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -15,6 +15,14 @@
* processing.
*/
class Robot : public frc::TimedRobot {
public:
Robot() {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
std::thread visionThread(VisionThread);
visionThread.detach();
}
private:
static void VisionThread() {
// Create an HTTP camera. The address will need to be modified to have the
@@ -50,13 +58,6 @@ class Robot : public frc::TimedRobot {
outputStream.PutFrame(mat);
}
}
void RobotInit() override {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
std::thread visionThread(VisionThread);
visionThread.detach();
}
};
#ifndef RUNNING_FRC_TESTS

View File

@@ -18,6 +18,19 @@
* processing.
*/
class Robot : public frc::TimedRobot {
public:
Robot() {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
#if defined(__linux__) || defined(_WIN32)
std::thread visionThread(VisionThread);
visionThread.detach();
#else
std::fputs("Vision only available on Linux or Windows.\n", stderr);
std::fflush(stderr);
#endif
}
#if defined(__linux__) || defined(_WIN32)
private:
@@ -55,18 +68,6 @@ class Robot : public frc::TimedRobot {
}
}
#endif
void RobotInit() override {
// We need to run our vision program in a separate thread. If not, our robot
// program will not run.
#if defined(__linux__) || defined(_WIN32)
std::thread visionThread(VisionThread);
visionThread.detach();
#else
std::fputs("Vision only available on Linux or Windows.\n", stderr);
std::fflush(stderr);
#endif
}
};
#ifndef RUNNING_FRC_TESTS

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -13,7 +13,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);

View File

@@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot {
static constexpr double kElevatorMinimumLength = 0.5;
public:
void RobotInit() override {
Robot() {
m_elevatorEncoder.SetDistancePerPulse(kMetersPerPulse);
// publish to dashboard

View File

@@ -33,7 +33,7 @@ class Robot : public frc::TimedRobot {
frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
}
void RobotInit() override {
Robot() {
// Use SetDistancePerPulse to set the multiplier for GetDistance
// This is set up assuming a 6 inch wheel with a 360 CPR encoder.
m_encoder.SetDistancePerPulse((std::numbers::pi * 6) / 360.0);

View File

@@ -11,11 +11,11 @@
* 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.
* robot class constructor.
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
#if defined(__linux__) || defined(_WIN32)
frc::CameraServer::StartAutomaticCapture();
#else

View File

@@ -4,7 +4,7 @@
#include "Robot.h"
void Robot::RobotInit() {
Robot::Robot() {
// Configure default commands and condition bindings on robot startup
m_robot.ConfigureBindings();
}

View File

@@ -27,7 +27,7 @@ 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 Robot::RobotInit().
* <p>Should be called in the robot class constructor.
*
* <p>Event binding methods are available on the frc2::Trigger class.
*/

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -6,7 +6,7 @@
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -29,7 +29,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
Robot() {
m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad},
frc::TrajectoryConfig(2_mps, 2_mps_sq));

View File

@@ -7,7 +7,7 @@
#include <frc/shuffleboard/Shuffleboard.h>
#include <units/pressure.h>
void Robot::RobotInit() {
Robot::Robot() {
// Publish elements to shuffleboard.
frc::ShuffleboardTab& tab = frc::Shuffleboard::GetTab("Pneumatics");
tab.Add("Single Solenoid", m_solenoid);

View File

@@ -35,7 +35,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void TeleopPeriodic() override;
private:

View File

@@ -93,7 +93,7 @@ class Robot : public frc::TimedRobot {
frc::TrapezoidProfile<units::radians>::State m_lastProfiledReference;
public:
void RobotInit() override {
Robot() {
// We go 2 pi radians per 4096 clicks.
m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
}

View File

@@ -92,7 +92,7 @@ class Robot : public frc::TimedRobot {
frc::TrapezoidProfile<units::meters>::State m_lastProfiledReference;
public:
void RobotInit() override {
Robot() {
// Circumference = pi * d, so distance per click = pi * d / counts
m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi * kDrumRadius.value() /
4096.0);

View File

@@ -80,7 +80,7 @@ class Robot : public frc::TimedRobot {
frc::XboxController m_joystick{kJoystickPort};
public:
void RobotInit() override {
Robot() {
// We go 2 pi radians per 4096 clicks.
m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
}

View File

@@ -80,7 +80,7 @@ class Robot : public frc::TimedRobot {
frc::XboxController m_joystick{kJoystickPort};
public:
void RobotInit() override {
Robot() {
// We go 2 pi radians per 4096 clicks.
m_encoder.SetDistancePerPulse(2.0 * std::numbers::pi / 4096.0);
}

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -6,7 +6,7 @@
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
void Robot::RobotPeriodic() {
frc2::CommandScheduler::GetInstance().Run();

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -21,7 +21,7 @@ class Robot : public frc::TimedRobot {
frc::Joystick m_rightStick{1};
public:
void RobotInit() override {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);

View File

@@ -20,7 +20,7 @@ class Robot : public frc::TimedRobot {
frc::XboxController m_driverController{0};
public:
void RobotInit() override {
Robot() {
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);

View File

@@ -8,7 +8,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <units/length.h>
void Robot::RobotInit() {
Robot::Robot() {
// Add the ultrasonic on the "Sensors" tab of the dashboard
// Data will update automatically
frc::Shuffleboard::GetTab("Sensors").Add(m_rangeFinder);

View File

@@ -13,7 +13,7 @@
*/
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void TeleopPeriodic() override;
void TestInit() override;
void TestPeriodic() override;

View File

@@ -6,7 +6,7 @@
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -6,7 +6,7 @@
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
/**
* This function is called every 20 ms, no matter the mode. Use

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -6,7 +6,7 @@
#include <frc2/command/CommandScheduler.h>
void Robot::RobotInit() {}
Robot::Robot() {}
void Robot::RobotPeriodic() {
frc2::CommandScheduler::GetInstance().Run();

View File

@@ -13,7 +13,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void DisabledInit() override;
void DisabledPeriodic() override;

View File

@@ -11,7 +11,7 @@
#include <hal/DriverStation.h>
#include <networktables/NetworkTable.h>
void Robot::RobotInit() {}
Robot::Robot() {}
void Robot::Disabled() {}
@@ -22,8 +22,6 @@ void Robot::Teleop() {}
void Robot::Test() {}
void Robot::StartCompetition() {
RobotInit();
frc::internal::DriverStationModeThread modeThread;
wpi::Event event{false, false};

View File

@@ -10,7 +10,7 @@
class Robot : public frc::RobotBase {
public:
void RobotInit();
Robot();
void Disabled();
void Autonomous();
void Teleop();

View File

@@ -7,7 +7,7 @@
#include <frc/smartdashboard/SmartDashboard.h>
#include <wpi/print.h>
void Robot::RobotInit() {
Robot::Robot() {
m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);

View File

@@ -11,7 +11,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;

View File

@@ -4,7 +4,7 @@
#include "Robot.h"
void Robot::RobotInit() {}
Robot::Robot() {}
void Robot::RobotPeriodic() {}
void Robot::AutonomousInit() {}

View File

@@ -8,7 +8,7 @@
class Robot : public frc::TimedRobot {
public:
void RobotInit() override;
Robot();
void RobotPeriodic() override;
void AutonomousInit() override;

View File

@@ -23,9 +23,7 @@ Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} {
// Total usage:
// 5 ms (robot) + 2 ms (controller 1) + 2 ms (controller 2) = 9 ms
// 9 ms / 10 ms -> 90% allocated
}
void Robot::RobotInit() {
m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);

View File

@@ -12,8 +12,6 @@
class Robot : public frc::TimesliceRobot {
public:
Robot();
void RobotInit() override;
void RobotPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;

View File

@@ -23,7 +23,6 @@ Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} {
// 9 ms / 10 ms -> 90% allocated
}
void Robot::RobotInit() {}
void Robot::RobotPeriodic() {}
void Robot::AutonomousInit() {}

View File

@@ -10,7 +10,6 @@ class Robot : public frc::TimesliceRobot {
public:
Robot();
void RobotInit() override;
void RobotPeriodic() override;
void AutonomousInit() override;

View File

@@ -97,9 +97,8 @@ public abstract class IterativeRobotBase extends RobotBase {
* <p>Users should override this method for default Robot-wide initialization which will be called
* when the robot is first powered on. It will be called exactly one time.
*
* <p>Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off
* until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to
* never indicate that the code is ready, causing the robot to be bypassed in a match.
* <p>Note: This method is functionally identical to the class constructor so that should be used
* instead.
*/
public void robotInit() {}

View File

@@ -45,10 +45,7 @@ class TimedRobotTest {
MockRobot() {
super(kPeriod);
}
@Override
public void robotInit() {
m_robotInitCount.addAndGet(1);
}

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.

Some files were not shown because too many files have changed in this diff Show More