Skip to content

Commit 6604b1d

Browse files
committed
Address more review comments
1 parent a944ceb commit 6604b1d

File tree

3 files changed

+53
-45
lines changed

3 files changed

+53
-45
lines changed

design-docs/opmodes.md

Lines changed: 9 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -150,16 +150,8 @@ The `OpModeRobot` class is the base class for the user's `Robot` class. It also
150150

151151
```java
152152
public abstract class OpModeRobot {
153-
public void disabledStart() {
154-
// this code is called when the robot enters disabled state (including at startup)
155-
}
156-
157-
public void disabledPeriodic() {
158-
// this code is called periodically while the robot is disabled
159-
}
160-
161-
public void disabledEnd() {
162-
// this code is called when the robot exits disabled state, prior to a opmode starting
153+
public void nonePeriodic() {
154+
// this code is called when no opmode is selected
163155
}
164156

165157
// these functions allow users to add opmodes without annotations
@@ -177,22 +169,24 @@ The full lifecycle of a opmode is as follows:
177169
- Operator selects opmode on DS -> opmode object is constructed
178170
- If different opmode is selected -> `opModeClose()` is called (which typically just calls `close()`), object is released to GC
179171
- While opmode is selected and robot is disabled, `disabledPeriodic()` is called
180-
- When the robot is enabled in the selected opmode, `opmodeRun()` is called; the result of this is different for different opmode base classes:
172+
- When the robot is enabled in the selected opmode, `opModeRun()` is called; the result of this is different for different opmode base classes:
181173
- `start()` is called once (for `PeriodicOpMode`)
182174
- `run()` is called (for `LinearOpMode`), or `periodic()` is called periodically (for `PeriodicOpMode`)
183175
- When the robot is disabled, `opModeStop()` is called (which results in `end()` being called for `PeriodicOpMode`), followed by `opModeClose()` (which results in `close()` being called for both `PeriodicOpMode` and `LinearOpMode`), object is released to GC
184176

185177
Following `opModeClose()` being called, a *new* opmode object is constructed based on the DS teleop/auto/test/match selector and selected opmode. In teleop/auto/test, the drop-down selection will be the same as before the previous enable, so the same opmode class is constructed again. In match (or when FMS-connected), only the selected auto opmode object is initially constructed; once auto completes, the selected teleop opmode object is constructed. Thus only zero or one opmode objects will ever be "alive" at any given time.
186178

187179
For consistency in operation, the library will ensure that `disabledPeriodic()` is always called at least once before `opModeRun()` is called.
188-
180+
- When the robot is enabled in the selected opmode, `opModeRun()` is called; the result of this is different for different opmode base classes:
189181
User implementations of opmode classes may have either a no-parameter constructor or a constructor that accepts the user's `Robot` class type. If available, the library will call the latter and pass the user's `Robot` object to it when constructing the class.
190182

191183
The library will use escalating steps to attempt to terminate a opmode if `opModeRun()` does not return within a reasonable timeframe after `opModeStop()` is called, up to and including termination of the robot executable process (which will result in an automatic restart of it at the system level). User code (particularly in `LinearOpMode` derived classes) should check for `isRunning()` returning false and return as quickly as possible to allow the opmode to terminate gracefully.
192184

193185
```java
194186
public interface OpMode {
195187
// this function is called periodically while the opmode is selected on the DS (robot is disabled)
188+
// Note: it may be called once when the robot is enabled to ensure it's always called once before
189+
// opModeRun() is called
196190
default void disabledPeriodic() {}
197191

198192
// this function is called when the opmode starts (robot is enabled)
@@ -225,7 +219,7 @@ public abstract class LinearOpMode implements OpMode {
225219
public abstract void run() throws InterruptedException:
226220

227221
public boolean isRunning() {
228-
// returns true until opModeEnd() is called
222+
// returns true until opModeStop() is called
229223
}
230224

231225
// implements OpMode interface
@@ -235,7 +229,7 @@ public abstract class LinearOpMode implements OpMode {
235229
}
236230

237231
@Override
238-
public final void opModeEnd() {
232+
public final void opModeStop() {
239233
// pseudo-code
240234
isRunning = false;
241235
}
@@ -282,10 +276,6 @@ public abstract class PeriodicOpMode implements OpMode {
282276
// returns the start time of the current loop in microseconds
283277
public final long getLoopStartTime() {...}
284278

285-
public boolean isRunning() {
286-
// returns true until opModeEnd() is called
287-
}
288-
289279
// implements OpMode interface
290280
@Override
291281
public final void opModeRun(long opModeId) {
@@ -487,6 +477,7 @@ Adding the following function enables maintaining the available opmode options l
487477

488478
`HAL_OpModeOption` is a structure describing each option:
489479
- `long id` - unique ID identifying the opmode (robot mode, name) pair. This encodes the robot mode in the upper bits, indicating which robot mode the opmode should be visible for (auto/teleop/test)
480+
- `string name`
490481
- `string group`
491482
- `string description`
492483
- `int textColor` - optional, used to set the text color for the option in the DS GUI

glass/src/libnt/native/cpp/NTFMS.cpp

Lines changed: 26 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,17 @@
1010

1111
#include <fmt/format.h>
1212

13-
#include "wpi/util/SmallVector.hpp"
14-
#include "wpi/util/timestamp.h"
13+
#include "wpi/util/Endian.hpp"
14+
15+
// FIXME: use dynamic struct decoding
16+
// Duplicated here from DriverStationTypes.h to avoid HAL dependency
17+
#define HAL_CONTROLWORD_OPMODE_HASH_MASK 0x00FFFFFFFFFFFFFFLL
18+
#define HAL_CONTROLWORD_ROBOT_MODE_MASK 0x0300000000000000LL
19+
#define HAL_CONTROLWORD_ROBOT_MODE_SHIFT 56
20+
#define HAL_CONTROLWORD_ENABLED_MASK 0x0400000000000000LL
21+
#define HAL_CONTROLWORD_ESTOP_MASK 0x0800000000000000LL
22+
#define HAL_CONTROLWORD_FMS_ATTACHED_MASK 0x1000000000000000LL
23+
#define HAL_CONTROLWORD_DS_ATTACHED_MASK 0x2000000000000000LL
1524

1625
using namespace wpi::glass;
1726

@@ -54,16 +63,24 @@ void NTFMSModel::Update() {
5463
m_allianceStationId.SetValue(v.value - 1 + 3 * (isRed ? 0 : 1), v.time);
5564
}
5665
for (auto&& v : m_controlWord.ReadQueue()) {
57-
if (v.value.size() != sizeof(uint8_t)) {
66+
if (v.value.size() != sizeof(uint64_t)) {
5867
continue;
5968
}
60-
uint8_t controlWord = v.value[0];
69+
uint64_t controlWord = wpi::util::support::endian::read64le(v.value.data());
6170
// See wpi::Struct<HAL_ControlWord> definition
62-
m_enabled.SetValue(((controlWord & 0x01) != 0) ? 1 : 0, v.time);
63-
m_robotMode.SetValue((controlWord & 0x06) >> 1, v.time);
64-
m_estop.SetValue(((controlWord & 0x08) != 0) ? 1 : 0, v.time);
65-
m_fmsAttached.SetValue(((controlWord & 0x10) != 0) ? 1 : 0, v.time);
66-
m_dsAttached.SetValue(((controlWord & 0x20) != 0) ? 1 : 0, v.time);
71+
m_enabled.SetValue(
72+
((controlWord & HAL_CONTROLWORD_ENABLED_MASK) != 0) ? 1 : 0, v.time);
73+
m_robotMode.SetValue((controlWord & HAL_CONTROLWORD_ROBOT_MODE_MASK) >>
74+
HAL_CONTROLWORD_ROBOT_MODE_SHIFT,
75+
v.time);
76+
m_estop.SetValue(((controlWord & HAL_CONTROLWORD_ESTOP_MASK) != 0) ? 1 : 0,
77+
v.time);
78+
m_fmsAttached.SetValue(
79+
((controlWord & HAL_CONTROLWORD_FMS_ATTACHED_MASK) != 0) ? 1 : 0,
80+
v.time);
81+
m_dsAttached.SetValue(
82+
((controlWord & HAL_CONTROLWORD_DS_ATTACHED_MASK) != 0) ? 1 : 0,
83+
v.time);
6784
}
6885
for (auto&& v : m_gameSpecificMessage.ReadQueue()) {
6986
m_gameSpecificMessageData.SetValue(std::move(v.value), v.time);

hal/src/main/java/org/wpilib/hardware/hal/ControlWord.java

Lines changed: 18 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -69,24 +69,6 @@ public void update(ControlWord word) {
6969
m_robotMode = word.m_robotMode;
7070
}
7171

72-
/**
73-
* Gets the Enabled flag.
74-
*
75-
* @return the Enabled flag
76-
*/
77-
public boolean isEnabled() {
78-
return (m_word & ENABLED_MASK) != 0;
79-
}
80-
81-
/**
82-
* Gets the robot mode.
83-
*
84-
* @return the robot mode
85-
*/
86-
public RobotMode getRobotMode() {
87-
return m_robotMode;
88-
}
89-
9072
/**
9173
* Gets the opmode ID.
9274
*
@@ -113,6 +95,24 @@ public void setOpModeId(long id) {
11395
m_robotMode = RobotMode.fromInt((int) ((m_word & ROBOT_MODE_MASK) >> ROBOT_MODE_SHIFT));
11496
}
11597

98+
/**
99+
* Gets the robot mode.
100+
*
101+
* @return the robot mode
102+
*/
103+
public RobotMode getRobotMode() {
104+
return m_robotMode;
105+
}
106+
107+
/**
108+
* Gets the Enabled flag.
109+
*
110+
* @return the Enabled flag
111+
*/
112+
public boolean isEnabled() {
113+
return (m_word & ENABLED_MASK) != 0;
114+
}
115+
116116
/**
117117
* Gets the E-Stop flag.
118118
*

0 commit comments

Comments
 (0)