Skip to content

Commit 922d795

Browse files
committed
[wpilib] Rename mode Init functions to Enter
Fixes #8717.
1 parent dfc8098 commit 922d795

102 files changed

Lines changed: 354 additions & 355 deletions

File tree

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

cameraserver/src/main/java/org/wpilib/vision/process/package-info.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -49,7 +49,7 @@
4949
* }
5050
*
5151
* {@literal @}Override
52-
* public void autonomousInit() {
52+
* public void autonomousEnter() {
5353
* findToteThread.start();
5454
* }
5555
*

developerRobot/src/main/java/wpilib/robot/Robot.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,15 +15,15 @@ public Robot() {}
1515

1616
/** This function is run once each time the robot enters autonomous mode. */
1717
@Override
18-
public void autonomousInit() {}
18+
public void autonomousEnter() {}
1919

2020
/** This function is called periodically during autonomous. */
2121
@Override
2222
public void autonomousPeriodic() {}
2323

2424
/** This function is called once each time the robot enters tele-operated mode. */
2525
@Override
26-
public void teleopInit() {}
26+
public void teleopEnter() {}
2727

2828
/** This function is called periodically during operator control. */
2929
@Override

developerRobot/src/main/native/cpp/Robot.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@ class Robot : public wpi::TimedRobot {
1515
/**
1616
* This function is run once each time the robot enters autonomous mode
1717
*/
18-
void AutonomousInit() override {}
18+
void AutonomousEnter() override {}
1919

2020
/**
2121
* This function is called periodically during autonomous
@@ -25,7 +25,7 @@ class Robot : public wpi::TimedRobot {
2525
/**
2626
* This function is called once each time the robot enters tele-operated mode
2727
*/
28-
void TeleopInit() override {}
28+
void TeleopEnter() override {}
2929

3030
/**
3131
* This function is called periodically during operator control

robotpyExamples/ArmSimulation/robot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ def __init__(self) -> None:
2222
def simulationPeriodic(self) -> None:
2323
self.arm.simulationPeriodic()
2424

25-
def teleopInit(self) -> None:
25+
def teleopEnter(self) -> None:
2626
self.arm.loadPreferences()
2727

2828
def teleopPeriodic(self) -> None:
@@ -33,6 +33,6 @@ def teleopPeriodic(self) -> None:
3333
# Otherwise, we disable the motor.
3434
self.arm.stop()
3535

36-
def disabledInit(self) -> None:
36+
def disabledEnter(self) -> None:
3737
# This just makes sure that our simulation code knows that the motor's off.
3838
self.arm.stop()

robotpyExamples/DriveDistanceOffboard/robot.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,13 @@ def __init__(self) -> None:
3939
# autonomous chooser on the dashboard.
4040
self.container = robotcontainer.RobotContainer()
4141

42-
def disabledInit(self) -> None:
42+
def disabledEnter(self) -> None:
4343
"""This function is called once each time the robot enters Disabled mode."""
4444

4545
def disabledPeriodic(self) -> None:
4646
"""This function is called periodically when disabled"""
4747

48-
def autonomousInit(self) -> None:
48+
def autonomousEnter(self) -> None:
4949
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
5050
self.autonomousCommand = self.container.getAutonomousCommand()
5151

@@ -58,7 +58,7 @@ def autonomousInit(self) -> None:
5858
def autonomousPeriodic(self) -> None:
5959
"""This function is called periodically during autonomous"""
6060

61-
def teleopInit(self) -> None:
61+
def teleopEnter(self) -> None:
6262
# This makes sure that the autonomous stops running when
6363
# teleop starts running. If you want the autonomous to
6464
# continue until interrupted by another command, remove
@@ -69,6 +69,6 @@ def teleopInit(self) -> None:
6969
def teleopPeriodic(self) -> None:
7070
"""This function is called periodically during operator control"""
7171

72-
def testInit(self) -> None:
72+
def testEnter(self) -> None:
7373
# Cancels all running commands at the start of test mode
7474
commands2.CommandScheduler.getInstance().cancelAll()

robotpyExamples/ElevatorExponentialSimulation/robot.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ def simulationPeriodic(self) -> None:
2727
# Update the simulation model.
2828
self.elevator.simulationPeriodic()
2929

30-
def teleopInit(self) -> None:
30+
def teleopEnter(self) -> None:
3131
self.elevator.reset()
3232

3333
def teleopPeriodic(self) -> None:
@@ -38,6 +38,6 @@ def teleopPeriodic(self) -> None:
3838
# Otherwise, we update the setpoint to 1 meter.
3939
self.elevator.reachGoal(constants.kLowerkSetpoint)
4040

41-
def disabledInit(self) -> None:
41+
def disabledEnter(self) -> None:
4242
# This just makes sure that our simulation code knows that the motor's off.
4343
self.elevator.stop()

robotpyExamples/ElevatorSimulation/robot.py

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,6 +35,6 @@ def teleopPeriodic(self) -> None:
3535
# Otherwise, we update the setpoint to 0.
3636
self.elevator.reachGoal(0.0)
3737

38-
def disabledInit(self) -> None:
38+
def disabledEnter(self) -> None:
3939
# This just makes sure that our simulation code knows that the motor's off.
4040
self.elevator.stop()

robotpyExamples/GettingStarted/robot.py

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,7 @@ def __init__(self):
2626
# gearbox is constructed, you might have to invert the left side instead.
2727
self.rightDrive.setInverted(True)
2828

29-
def autonomousInit(self):
29+
def autonomousEnter(self):
3030
"""This function is run once each time the robot enters autonomous mode."""
3131
self.timer.restart()
3232

@@ -40,7 +40,7 @@ def autonomousPeriodic(self):
4040
else:
4141
self.robotDrive.stopMotor() # Stop robot
4242

43-
def teleopInit(self):
43+
def teleopEnter(self):
4444
"""This function is called once each time the robot enters teleoperated mode."""
4545

4646
def teleopPeriodic(self):
@@ -49,7 +49,7 @@ def teleopPeriodic(self):
4949
-self.controller.getLeftY(), -self.controller.getRightX()
5050
)
5151

52-
def testInit(self):
52+
def testEnter(self):
5353
"""This function is called once each time the robot enters test mode."""
5454

5555
def testPeriodic(self):

robotpyExamples/HatchbotInlined/robot.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,13 @@ def __init__(self) -> None:
3939
# Change to `false` to not record joystick data.
4040
wpilib.DriverStation.startDataLog(wpilib.DataLogManager.getLog(), True)
4141

42-
def disabledInit(self) -> None:
42+
def disabledEnter(self) -> None:
4343
"""This function is called once each time the robot enters Disabled mode."""
4444

4545
def disabledPeriodic(self) -> None:
4646
"""This function is called periodically when disabled"""
4747

48-
def autonomousInit(self) -> None:
48+
def autonomousEnter(self) -> None:
4949
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
5050
self.autonomousCommand = self.container.getAutonomousCommand()
5151

@@ -55,7 +55,7 @@ def autonomousInit(self) -> None:
5555
def autonomousPeriodic(self) -> None:
5656
"""This function is called periodically during autonomous"""
5757

58-
def teleopInit(self) -> None:
58+
def teleopEnter(self) -> None:
5959
# This makes sure that the autonomous stops running when
6060
# teleop starts running. If you want the autonomous to
6161
# continue until interrupted by another command, remove
@@ -66,6 +66,6 @@ def teleopInit(self) -> None:
6666
def teleopPeriodic(self) -> None:
6767
"""This function is called periodically during operator control"""
6868

69-
def testInit(self) -> None:
69+
def testEnter(self) -> None:
7070
# Cancels all running commands at the start of test mode
7171
commands2.CommandScheduler.getInstance().cancelAll()

robotpyExamples/HatchbotTraditional/robot.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -39,13 +39,13 @@ def __init__(self) -> None:
3939
# Change to `false` to not record joystick data.
4040
wpilib.DriverStation.startDataLog(wpilib.DataLogManager.getLog(), True)
4141

42-
def disabledInit(self) -> None:
42+
def disabledEnter(self) -> None:
4343
"""This function is called once each time the robot enters Disabled mode."""
4444

4545
def disabledPeriodic(self) -> None:
4646
"""This function is called periodically when disabled"""
4747

48-
def autonomousInit(self) -> None:
48+
def autonomousEnter(self) -> None:
4949
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
5050
self.autonomousCommand = self.container.getAutonomousCommand()
5151

@@ -55,7 +55,7 @@ def autonomousInit(self) -> None:
5555
def autonomousPeriodic(self) -> None:
5656
"""This function is called periodically during autonomous"""
5757

58-
def teleopInit(self) -> None:
58+
def teleopEnter(self) -> None:
5959
# This makes sure that the autonomous stops running when
6060
# teleop starts running. If you want the autonomous to
6161
# continue until interrupted by another command, remove
@@ -66,6 +66,6 @@ def teleopInit(self) -> None:
6666
def teleopPeriodic(self) -> None:
6767
"""This function is called periodically during operator control"""
6868

69-
def testInit(self) -> None:
69+
def testEnter(self) -> None:
7070
# Cancels all running commands at the start of test mode
7171
commands2.CommandScheduler.getInstance().cancelAll()

0 commit comments

Comments
 (0)