001/*----------------------------------------------------------------------------*/ 002/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */ 003/* Open Source Software - may be modified and shared by FRC teams. The code */ 004/* must be accompanied by the FIRST BSD license file in the root directory of */ 005/* the project. */ 006/*----------------------------------------------------------------------------*/ 007 008package edu.wpi.first.wpilibj; 009 010import edu.wpi.first.wpilibj.hal.HAL; 011import edu.wpi.first.wpilibj.livewindow.LiveWindow; 012import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; 013 014/** 015 * IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase 016 * class. 017 * 018 * <p>The IterativeRobotBase class does not implement startCompetition(), so it should not be used 019 * by teams directly. 020 * 021 * <p>This class provides the following functions which are called by the main loop, 022 * startCompetition(), at the appropriate times: 023 * 024 * <p>robotInit() -- provide for initialization at robot power-on 025 * 026 * <p>init() functions -- each of the following functions is called once when the 027 * appropriate mode is entered: 028 * - disabledInit() -- called only when first disabled 029 * - autonomousInit() -- called each and every time autonomous is entered from 030 * another mode 031 * - teleopInit() -- called each and every time teleop is entered from 032 * another mode 033 * - testInit() -- called each and every time test is entered from 034 * another mode 035 * 036 * <p>periodic() functions -- each of these functions is called on an interval: 037 * - robotPeriodic() 038 * - disabledPeriodic() 039 * - autonomousPeriodic() 040 * - teleopPeriodic() 041 * - testPeriodic() 042 */ 043public abstract class IterativeRobotBase extends RobotBase { 044 private enum Mode { 045 kNone, 046 kDisabled, 047 kAutonomous, 048 kTeleop, 049 kTest 050 } 051 052 private Mode m_lastMode = Mode.kNone; 053 054 /** 055 * Provide an alternate "main loop" via startCompetition(). 056 */ 057 public abstract void startCompetition(); 058 059 /* ----------- Overridable initialization code ----------------- */ 060 061 /** 062 * Robot-wide initialization code should go here. 063 * 064 * <p>Users should override this method for default Robot-wide initialization which will be called 065 * when the robot is first powered on. It will be called exactly one time. 066 * 067 * <p>Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off 068 * until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to 069 * never indicate that the code is ready, causing the robot to be bypassed in a match. 070 */ 071 public void robotInit() { 072 System.out.println("Default robotInit() method... Overload me!"); 073 } 074 075 /** 076 * Initialization code for disabled mode should go here. 077 * 078 * <p>Users should override this method for initialization code which will be called each time the 079 * robot enters disabled mode. 080 */ 081 public void disabledInit() { 082 System.out.println("Default disabledInit() method... Overload me!"); 083 } 084 085 /** 086 * Initialization code for autonomous mode should go here. 087 * 088 * <p>Users should override this method for initialization code which will be called each time the 089 * robot enters autonomous mode. 090 */ 091 public void autonomousInit() { 092 System.out.println("Default autonomousInit() method... Overload me!"); 093 } 094 095 /** 096 * Initialization code for teleop mode should go here. 097 * 098 * <p>Users should override this method for initialization code which will be called each time the 099 * robot enters teleop mode. 100 */ 101 public void teleopInit() { 102 System.out.println("Default teleopInit() method... Overload me!"); 103 } 104 105 /** 106 * Initialization code for test mode should go here. 107 * 108 * <p>Users should override this method for initialization code which will be called each time the 109 * robot enters test mode. 110 */ 111 @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation") 112 public void testInit() { 113 System.out.println("Default testInit() method... Overload me!"); 114 } 115 116 /* ----------- Overridable periodic code ----------------- */ 117 118 private boolean m_rpFirstRun = true; 119 120 /** 121 * Periodic code for all robot modes should go here. 122 */ 123 public void robotPeriodic() { 124 if (m_rpFirstRun) { 125 System.out.println("Default robotPeriodic() method... Overload me!"); 126 m_rpFirstRun = false; 127 } 128 } 129 130 private boolean m_dpFirstRun = true; 131 132 /** 133 * Periodic code for disabled mode should go here. 134 */ 135 public void disabledPeriodic() { 136 if (m_dpFirstRun) { 137 System.out.println("Default disabledPeriodic() method... Overload me!"); 138 m_dpFirstRun = false; 139 } 140 } 141 142 private boolean m_apFirstRun = true; 143 144 /** 145 * Periodic code for autonomous mode should go here. 146 */ 147 public void autonomousPeriodic() { 148 if (m_apFirstRun) { 149 System.out.println("Default autonomousPeriodic() method... Overload me!"); 150 m_apFirstRun = false; 151 } 152 } 153 154 private boolean m_tpFirstRun = true; 155 156 /** 157 * Periodic code for teleop mode should go here. 158 */ 159 public void teleopPeriodic() { 160 if (m_tpFirstRun) { 161 System.out.println("Default teleopPeriodic() method... Overload me!"); 162 m_tpFirstRun = false; 163 } 164 } 165 166 private boolean m_tmpFirstRun = true; 167 168 /** 169 * Periodic code for test mode should go here. 170 */ 171 @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation") 172 public void testPeriodic() { 173 if (m_tmpFirstRun) { 174 System.out.println("Default testPeriodic() method... Overload me!"); 175 m_tmpFirstRun = false; 176 } 177 } 178 179 protected void loopFunc() { 180 // Call the appropriate function depending upon the current robot mode 181 if (isDisabled()) { 182 // call DisabledInit() if we are now just entering disabled mode from 183 // either a different mode or from power-on 184 if (m_lastMode != Mode.kDisabled) { 185 LiveWindow.setEnabled(false); 186 disabledInit(); 187 m_lastMode = Mode.kDisabled; 188 } 189 HAL.observeUserProgramDisabled(); 190 disabledPeriodic(); 191 } else if (isAutonomous()) { 192 // call Autonomous_Init() if this is the first time 193 // we've entered autonomous_mode 194 if (m_lastMode != Mode.kAutonomous) { 195 LiveWindow.setEnabled(false); 196 // KBS NOTE: old code reset all PWMs and relays to "safe values" 197 // whenever entering autonomous mode, before calling 198 // "Autonomous_Init()" 199 autonomousInit(); 200 m_lastMode = Mode.kAutonomous; 201 } 202 HAL.observeUserProgramAutonomous(); 203 autonomousPeriodic(); 204 } else if (isOperatorControl()) { 205 // call Teleop_Init() if this is the first time 206 // we've entered teleop_mode 207 if (m_lastMode != Mode.kTeleop) { 208 LiveWindow.setEnabled(false); 209 teleopInit(); 210 m_lastMode = Mode.kTeleop; 211 } 212 HAL.observeUserProgramTeleop(); 213 teleopPeriodic(); 214 } else { 215 // call TestInit() if we are now just entering test mode from either 216 // a different mode or from power-on 217 if (m_lastMode != Mode.kTest) { 218 LiveWindow.setEnabled(true); 219 testInit(); 220 m_lastMode = Mode.kTest; 221 } 222 HAL.observeUserProgramTest(); 223 testPeriodic(); 224 } 225 robotPeriodic(); 226 SmartDashboard.updateValues(); 227 LiveWindow.updateValues(); 228 } 229}