mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
It's only syntactic sugar over the CommandScheduler's schedule method and creates a footgun because it’s too obvious to try to use in incorrect places. Co-authored-by: Starlight220 <53231611+Starlight220@users.noreply.github.com>
73 lines
1.9 KiB
C++
73 lines
1.9 KiB
C++
// Copyright (c) FIRST and other WPILib contributors.
|
|
// Open Source Software; you can modify and/or share it under the terms of
|
|
// the WPILib BSD license file in the root directory of this project.
|
|
|
|
#include "Robot.h"
|
|
|
|
#include <frc/smartdashboard/SmartDashboard.h>
|
|
#include <frc2/command/CommandScheduler.h>
|
|
|
|
Robot::Robot() {}
|
|
|
|
/**
|
|
* This function is called every 20 ms, no matter the mode. Use
|
|
* this for items like diagnostics that you want to run during disabled,
|
|
* autonomous, teleoperated and test.
|
|
*
|
|
* <p> This runs after the mode specific periodic functions, but before
|
|
* LiveWindow and SmartDashboard integrated updating.
|
|
*/
|
|
void Robot::RobotPeriodic() {
|
|
frc2::CommandScheduler::GetInstance().Run();
|
|
}
|
|
|
|
/**
|
|
* This function is called once each time the robot enters Disabled mode. You
|
|
* can use it to reset any subsystem information you want to clear when the
|
|
* robot is disabled.
|
|
*/
|
|
void Robot::DisabledInit() {}
|
|
|
|
void Robot::DisabledPeriodic() {}
|
|
|
|
/**
|
|
* This autonomous runs the autonomous command selected by your {@link
|
|
* RobotContainer} class.
|
|
*/
|
|
void Robot::AutonomousInit() {
|
|
m_autonomousCommand = m_container.GetAutonomousCommand();
|
|
|
|
if (m_autonomousCommand) {
|
|
frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value());
|
|
}
|
|
}
|
|
|
|
void Robot::AutonomousPeriodic() {}
|
|
|
|
void Robot::TeleopInit() {
|
|
// This makes sure that the autonomous stops running when
|
|
// teleop starts running. If you want the autonomous to
|
|
// continue until interrupted by another command, remove
|
|
// this line or comment it out.
|
|
if (m_autonomousCommand) {
|
|
m_autonomousCommand->Cancel();
|
|
m_autonomousCommand.reset();
|
|
}
|
|
}
|
|
|
|
/**
|
|
* This function is called periodically during operator control.
|
|
*/
|
|
void Robot::TeleopPeriodic() {}
|
|
|
|
/**
|
|
* This function is called periodically during test mode.
|
|
*/
|
|
void Robot::TestPeriodic() {}
|
|
|
|
#ifndef RUNNING_FRC_TESTS
|
|
int main() {
|
|
return frc::StartRobot<Robot>();
|
|
}
|
|
#endif
|