blob: 3b4e64ffac58f2c6123d4a8353f2b5d69a81fcd3 [file] [log] [blame]
Brian Silvermanf7f267a2017-02-04 16:16:08 -08001/*----------------------------------------------------------------------------*/
2/* Copyright (c) FIRST 2008-2017. All Rights Reserved. */
3/* Open Source Software - may be modified and shared by FRC teams. The code */
4/* must be accompanied by the FIRST BSD license file in the root directory of */
5/* the project. */
6/*----------------------------------------------------------------------------*/
7
8#include "IterativeRobot.h"
9
10#include "DriverStation.h"
11#include "HAL/HAL.h"
12#include "LiveWindow/LiveWindow.h"
13#include "networktables/NetworkTable.h"
14
15using namespace frc;
16
17/**
18 * Provide an alternate "main loop" via StartCompetition().
19 *
20 * This specific StartCompetition() implements "main loop" behaviour synced with
21 * the DS packets.
22 */
23void IterativeRobot::StartCompetition() {
24 HAL_Report(HALUsageReporting::kResourceType_Framework,
25 HALUsageReporting::kFramework_Iterative);
26
27 LiveWindow* lw = LiveWindow::GetInstance();
28 // first and one-time initialization
29 NetworkTable::GetTable("LiveWindow")
30 ->GetSubTable("~STATUS~")
31 ->PutBoolean("LW Enabled", false);
32 RobotInit();
33
34 // Tell the DS that the robot is ready to be enabled
35 HAL_ObserveUserProgramStarting();
36
37 // loop forever, calling the appropriate mode-dependent function
38 lw->SetEnabled(false);
39 while (true) {
40 // wait for driver station data so the loop doesn't hog the CPU
41 m_ds.WaitForData();
42 // Call the appropriate function depending upon the current robot mode
43 if (IsDisabled()) {
44 // call DisabledInit() if we are now just entering disabled mode from
45 // either a different mode or from power-on
46 if (!m_disabledInitialized) {
47 lw->SetEnabled(false);
48 DisabledInit();
49 m_disabledInitialized = true;
50 // reset the initialization flags for the other modes
51 m_autonomousInitialized = false;
52 m_teleopInitialized = false;
53 m_testInitialized = false;
54 }
55 HAL_ObserveUserProgramDisabled();
56 DisabledPeriodic();
57 } else if (IsAutonomous()) {
58 // call AutonomousInit() if we are now just entering autonomous mode from
59 // either a different mode or from power-on
60 if (!m_autonomousInitialized) {
61 lw->SetEnabled(false);
62 AutonomousInit();
63 m_autonomousInitialized = true;
64 // reset the initialization flags for the other modes
65 m_disabledInitialized = false;
66 m_teleopInitialized = false;
67 m_testInitialized = false;
68 }
69 HAL_ObserveUserProgramAutonomous();
70 AutonomousPeriodic();
71 } else if (IsTest()) {
72 // call TestInit() if we are now just entering test mode from
73 // either a different mode or from power-on
74 if (!m_testInitialized) {
75 lw->SetEnabled(true);
76 TestInit();
77 m_testInitialized = true;
78 // reset the initialization flags for the other modes
79 m_disabledInitialized = false;
80 m_autonomousInitialized = false;
81 m_teleopInitialized = false;
82 }
83 HAL_ObserveUserProgramTest();
84 TestPeriodic();
85 } else {
86 // call TeleopInit() if we are now just entering teleop mode from
87 // either a different mode or from power-on
88 if (!m_teleopInitialized) {
89 lw->SetEnabled(false);
90 TeleopInit();
91 m_teleopInitialized = true;
92 // reset the initialization flags for the other modes
93 m_disabledInitialized = false;
94 m_autonomousInitialized = false;
95 m_testInitialized = false;
96 Scheduler::GetInstance()->SetEnabled(true);
97 }
98 HAL_ObserveUserProgramTeleop();
99 TeleopPeriodic();
100 }
101 RobotPeriodic();
102 }
103}
104
105/**
106 * Robot-wide initialization code should go here.
107 *
108 * Users should override this method for default Robot-wide initialization which
109 * will be called when the robot is first powered on. It will be called exactly
110 * one time.
111 *
112 * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
113 * indicators will be off until RobotInit() exits. Code in RobotInit() that
114 * waits for enable will cause the robot to never indicate that the code is
115 * ready, causing the robot to be bypassed in a match.
116 */
117void IterativeRobot::RobotInit() {
118 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
119}
120
121/**
122 * Initialization code for disabled mode should go here.
123 *
124 * Users should override this method for initialization code which will be
125 * called each time
126 * the robot enters disabled mode.
127 */
128void IterativeRobot::DisabledInit() {
129 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
130}
131
132/**
133 * Initialization code for autonomous mode should go here.
134 *
135 * Users should override this method for initialization code which will be
136 * called each time the robot enters autonomous mode.
137 */
138void IterativeRobot::AutonomousInit() {
139 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
140}
141
142/**
143 * Initialization code for teleop mode should go here.
144 *
145 * Users should override this method for initialization code which will be
146 * called each time the robot enters teleop mode.
147 */
148void IterativeRobot::TeleopInit() {
149 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
150}
151
152/**
153 * Initialization code for test mode should go here.
154 *
155 * Users should override this method for initialization code which will be
156 * called each time the robot enters test mode.
157 */
158void IterativeRobot::TestInit() {
159 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
160}
161
162/**
163 * Periodic code for all modes should go here.
164 *
165 * This function is called each time a new packet is received from the driver
166 * station.
167 *
168 * Packets are received approximately every 20ms. Fixed loop timing is not
169 * guaranteed due to network timing variability and the function may not be
170 * called at all if the Driver Station is disconnected. For most use cases the
171 * variable timing will not be an issue. If your code does require guaranteed
172 * fixed periodic timing, consider using Notifier or PIDController instead.
173 */
174void IterativeRobot::RobotPeriodic() {
175 static bool firstRun = true;
176 if (firstRun) {
177 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
178 firstRun = false;
179 }
180}
181
182/**
183 * Periodic code for disabled mode should go here.
184 *
185 * Users should override this method for code which will be called each time a
186 * new packet is received from the driver station and the robot is in disabled
187 * mode.
188 *
189 * Packets are received approximately every 20ms. Fixed loop timing is not
190 * guaranteed due to network timing variability and the function may not be
191 * called at all if the Driver Station is disconnected. For most use cases the
192 * variable timing will not be an issue. If your code does require guaranteed
193 * fixed periodic timing, consider using Notifier or PIDController instead.
194 */
195void IterativeRobot::DisabledPeriodic() {
196 static bool firstRun = true;
197 if (firstRun) {
198 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
199 firstRun = false;
200 }
201}
202
203/**
204 * Periodic code for autonomous mode should go here.
205 *
206 * Users should override this method for code which will be called each time a
207 * new packet is received from the driver station and the robot is in autonomous
208 * mode.
209 *
210 * Packets are received approximately every 20ms. Fixed loop timing is not
211 * guaranteed due to network timing variability and the function may not be
212 * called at all if the Driver Station is disconnected. For most use cases the
213 * variable timing will not be an issue. If your code does require guaranteed
214 * fixed periodic timing, consider using Notifier or PIDController instead.
215 */
216void IterativeRobot::AutonomousPeriodic() {
217 static bool firstRun = true;
218 if (firstRun) {
219 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
220 firstRun = false;
221 }
222}
223
224/**
225 * Periodic code for teleop mode should go here.
226 *
227 * Users should override this method for code which will be called each time a
228 * new packet is received from the driver station and the robot is in teleop
229 * mode.
230 *
231 * Packets are received approximately every 20ms. Fixed loop timing is not
232 * guaranteed due to network timing variability and the function may not be
233 * called at all if the Driver Station is disconnected. For most use cases the
234 * variable timing will not be an issue. If your code does require guaranteed
235 * fixed periodic timing, consider using Notifier or PIDController instead.
236 */
237void IterativeRobot::TeleopPeriodic() {
238 static bool firstRun = true;
239 if (firstRun) {
240 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
241 firstRun = false;
242 }
243}
244
245/**
246 * Periodic code for test mode should go here.
247 *
248 * Users should override this method for code which will be called each time a
249 * new packet is received from the driver station and the robot is in test mode.
250 *
251 * Packets are received approximately every 20ms. Fixed loop timing is not
252 * guaranteed due to network timing variability and the function may not be
253 * called at all if the Driver Station is disconnected. For most use cases the
254 * variable timing will not be an issue. If your code does require guaranteed
255 * fixed periodic timing, consider using Notifier or PIDController instead.
256 */
257void IterativeRobot::TestPeriodic() {
258 static bool firstRun = true;
259 if (firstRun) {
260 std::printf("Default %s() method... Overload me!\n", __FUNCTION__);
261 firstRun = false;
262 }
263}