mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
72 lines
2.4 KiB
Python
72 lines
2.4 KiB
Python
|
|
#!/usr/bin/env python3
|
||
|
|
#
|
||
|
|
# 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.
|
||
|
|
#
|
||
|
|
|
||
|
|
import typing
|
||
|
|
|
||
|
|
import commands2
|
||
|
|
import wpilib
|
||
|
|
|
||
|
|
from robotcontainer import RobotContainer
|
||
|
|
|
||
|
|
|
||
|
|
class MyRobot(commands2.TimedCommandRobot):
|
||
|
|
"""
|
||
|
|
Command v2 robots are encouraged to inherit from TimedCommandRobot, which
|
||
|
|
has an implementation of robotPeriodic which runs the scheduler for you
|
||
|
|
"""
|
||
|
|
|
||
|
|
autonomousCommand: typing.Optional[commands2.Command] = None
|
||
|
|
|
||
|
|
def __init__(self) -> None:
|
||
|
|
"""
|
||
|
|
This function is run when the robot is first started up and should be used for any
|
||
|
|
initialization code.
|
||
|
|
"""
|
||
|
|
super().__init__()
|
||
|
|
|
||
|
|
# Instantiate our RobotContainer. This will perform all our button bindings, and put our
|
||
|
|
# autonomous chooser on the dashboard.
|
||
|
|
self.container = RobotContainer()
|
||
|
|
|
||
|
|
# Start recording to data log
|
||
|
|
wpilib.DataLogManager.start()
|
||
|
|
|
||
|
|
# Record DS control and joystick data.
|
||
|
|
# Change to `false` to not record joystick data.
|
||
|
|
wpilib.DriverStation.startDataLog(wpilib.DataLogManager.getLog(), True)
|
||
|
|
|
||
|
|
def disabledInit(self) -> None:
|
||
|
|
"""This function is called once each time the robot enters Disabled mode."""
|
||
|
|
|
||
|
|
def disabledPeriodic(self) -> None:
|
||
|
|
"""This function is called periodically when disabled"""
|
||
|
|
|
||
|
|
def autonomousInit(self) -> None:
|
||
|
|
"""This autonomous runs the autonomous command selected by your RobotContainer class."""
|
||
|
|
self.autonomousCommand = self.container.getAutonomousCommand()
|
||
|
|
|
||
|
|
if self.autonomousCommand:
|
||
|
|
self.autonomousCommand.schedule()
|
||
|
|
|
||
|
|
def autonomousPeriodic(self) -> None:
|
||
|
|
"""This function is called periodically during autonomous"""
|
||
|
|
|
||
|
|
def teleopInit(self) -> None:
|
||
|
|
# 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 self.autonomousCommand:
|
||
|
|
self.autonomousCommand.cancel()
|
||
|
|
|
||
|
|
def teleopPeriodic(self) -> None:
|
||
|
|
"""This function is called periodically during operator control"""
|
||
|
|
|
||
|
|
def testInit(self) -> None:
|
||
|
|
# Cancels all running commands at the start of test mode
|
||
|
|
commands2.CommandScheduler.getInstance().cancelAll()
|