IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class.
More...
#include <wpi/framework/IterativeRobotBase.hpp>
|
| static bool | IsEnabled () |
| | Determine if the Robot is currently enabled.
|
| static bool | IsDisabled () |
| | Determine if the Robot is currently disabled.
|
| static bool | IsAutonomous () |
| | Determine if the robot is currently in Autonomous mode.
|
| static bool | IsAutonomousEnabled () |
| | Determine if the robot is currently in Autonomous mode and enabled.
|
| static bool | IsTeleop () |
| | Determine if the robot is currently in Operator Control mode.
|
| static bool | IsTeleopEnabled () |
| | Determine if the robot is current in Operator Control mode and enabled.
|
| static bool | IsTest () |
| | Determine if the robot is currently in Test mode.
|
| static bool | IsTestEnabled () |
| | Determine if the robot is current in Test mode and enabled.
|
| static int64_t | GetOpModeId () |
| | Gets the currently selected operating mode of the driver station.
|
| static std::string | GetOpMode () |
| | Gets the currently selected operating mode of the driver station.
|
| static std::thread::id | GetThreadId () |
| | Returns the main thread ID.
|
| static RuntimeType | GetRuntimeType () |
| | Get the current runtime type.
|
| static constexpr bool | IsReal () |
| | Get if the robot is real.
|
| static constexpr bool | IsSimulation () |
| | Get if the robot is a simulation.
|
| NT_Listener | connListenerHandle |
| static std::thread::id | m_threadId |
IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase class.
The IterativeRobotBase class does not implement StartCompetition(), so it should not be used by teams directly.
This class provides the following functions which are called by the main loop, StartCompetition(), at the appropriate times:
DriverStationConnected() – provide for initialization the first time the DS is connected
Init() functions – each of the following functions is called once when the appropriate mode is entered:
- DisabledInit() – called each and every time disabled is entered from another mode
- AutonomousInit() – called each and every time autonomous is entered from another mode
- TeleopInit() – called each and every time teleop is entered from another mode
- TestInit() – called each and every time test is entered from another mode
Periodic() functions – each of these functions is called on an interval:
Exit() functions – each of the following functions is called once when the appropriate mode is exited:
◆ IterativeRobotBase() [1/2]
| wpi::IterativeRobotBase::IterativeRobotBase |
( |
wpi::units::second_t | period | ) |
|
|
explicit |
◆ ~IterativeRobotBase()
| wpi::IterativeRobotBase::~IterativeRobotBase |
( |
| ) |
|
|
overridedefault |
◆ IterativeRobotBase() [2/2]
| wpi::IterativeRobotBase::IterativeRobotBase |
( |
IterativeRobotBase && | | ) |
|
|
protecteddefault |
◆ AutonomousExit()
| virtual void wpi::IterativeRobotBase::AutonomousExit |
( |
| ) |
|
|
virtual |
Exit code for autonomous mode should go here.
Users should override this method for code which will be called each time the robot exits autonomous mode.
◆ AutonomousInit()
| virtual void wpi::IterativeRobotBase::AutonomousInit |
( |
| ) |
|
|
virtual |
Initialization code for autonomous mode should go here.
Users should override this method for initialization code which will be called each time the robot enters autonomous mode.
◆ AutonomousPeriodic()
| virtual void wpi::IterativeRobotBase::AutonomousPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for autonomous mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in autonomous mode.
◆ DisabledExit()
| virtual void wpi::IterativeRobotBase::DisabledExit |
( |
| ) |
|
|
virtual |
Exit code for disabled mode should go here.
Users should override this method for code which will be called each time the robot exits disabled mode.
◆ DisabledInit()
| virtual void wpi::IterativeRobotBase::DisabledInit |
( |
| ) |
|
|
virtual |
Initialization code for disabled mode should go here.
Users should override this method for initialization code which will be called each time the robot enters disabled mode.
◆ DisabledPeriodic()
| virtual void wpi::IterativeRobotBase::DisabledPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for disabled mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in disabled mode.
◆ DriverStationConnected()
| virtual void wpi::IterativeRobotBase::DriverStationConnected |
( |
| ) |
|
|
virtual |
Code that needs to know the DS state should go here.
Users should override this method for initialization that needs to occur after the DS is connected, such as needing the alliance information.
◆ GetPeriod()
| wpi::units::second_t wpi::IterativeRobotBase::GetPeriod |
( |
| ) |
const |
Gets time period between calls to Periodic() functions.
◆ LoopFunc()
| void wpi::IterativeRobotBase::LoopFunc |
( |
| ) |
|
|
protected |
◆ operator=()
◆ PrintWatchdogEpochs()
| void wpi::IterativeRobotBase::PrintWatchdogEpochs |
( |
| ) |
|
Prints list of epochs added so far and their times.
◆ RobotPeriodic()
| virtual void wpi::IterativeRobotBase::RobotPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for all modes should go here.
This function is called each time a new packet is received from the driver station.
◆ SetNetworkTablesFlushEnabled()
| void wpi::IterativeRobotBase::SetNetworkTablesFlushEnabled |
( |
bool | enabled | ) |
|
Enables or disables flushing NetworkTables every loop iteration.
By default, this is enabled.
- Parameters
-
| enabled | True to enable, false to disable |
- Deprecated
- Deprecated without replacement.
◆ SimulationInit()
| virtual void wpi::IterativeRobotBase::SimulationInit |
( |
| ) |
|
|
virtual |
Robot-wide simulation initialization code should go here.
Users should override this method for default Robot-wide simulation related initialization which will be called when the robot is first started. It will be called exactly one time after the robot class constructor is called only when the robot is in simulation.
◆ SimulationPeriodic()
| virtual void wpi::IterativeRobotBase::SimulationPeriodic |
( |
| ) |
|
|
virtual |
Periodic simulation code should go here.
This function is called in a simulated robot after user code executes.
◆ TeleopExit()
| virtual void wpi::IterativeRobotBase::TeleopExit |
( |
| ) |
|
|
virtual |
Exit code for teleop mode should go here.
Users should override this method for code which will be called each time the robot exits teleop mode.
◆ TeleopInit()
| virtual void wpi::IterativeRobotBase::TeleopInit |
( |
| ) |
|
|
virtual |
Initialization code for teleop mode should go here.
Users should override this method for initialization code which will be called each time the robot enters teleop mode.
◆ TeleopPeriodic()
| virtual void wpi::IterativeRobotBase::TeleopPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for teleop mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in teleop mode.
◆ TestExit()
| virtual void wpi::IterativeRobotBase::TestExit |
( |
| ) |
|
|
virtual |
Exit code for test mode should go here.
Users should override this method for code which will be called each time the robot exits test mode.
◆ TestInit()
| virtual void wpi::IterativeRobotBase::TestInit |
( |
| ) |
|
|
virtual |
Initialization code for test mode should go here.
Users should override this method for initialization code which will be called each time the robot enters test mode.
◆ TestPeriodic()
| virtual void wpi::IterativeRobotBase::TestPeriodic |
( |
| ) |
|
|
virtual |
Periodic code for test mode should go here.
Users should override this method for code which will be called each time a new packet is received from the driver station and the robot is in test mode.
The documentation for this class was generated from the following file: