Skip to content

Commit

Permalink
[hal] Fix interrupt edges being flipped in sim (#6720)
Browse files Browse the repository at this point in the history
  • Loading branch information
Gold856 authored Jul 17, 2024
1 parent 59256f0 commit e5b7cf4
Show file tree
Hide file tree
Showing 3 changed files with 160 additions and 20 deletions.
40 changes: 22 additions & 18 deletions hal/src/main/native/sim/Interrupts.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ struct Interrupt {
HAL_AnalogTriggerType trigType;
int64_t risingTimestamp;
int64_t fallingTimestamp;
bool previousState;
bool currentState;
bool fireOnUp;
bool fireOnDown;
int32_t callbackId;
Expand Down Expand Up @@ -121,8 +121,8 @@ static void ProcessInterruptDigitalSynchronous(const char* name, void* param,
return;
}
bool retVal = value->data.v_boolean;
auto previousState = interrupt->previousState;
interrupt->previousState = retVal;
auto previousState = interrupt->currentState;
interrupt->currentState = retVal;
// If no change in interrupt, return;
if (retVal == previousState) {
return;
Expand Down Expand Up @@ -176,8 +176,8 @@ static void ProcessInterruptAnalogSynchronous(const char* name, void* param,
// Pulse interrupt
interruptData->waitCond.notify_all();
}
auto previousState = interrupt->previousState;
interrupt->previousState = retVal;
auto previousState = interrupt->currentState;
interrupt->currentState = retVal;
// If no change in interrupt, return;
if (retVal == previousState) {
return;
Expand Down Expand Up @@ -220,7 +220,7 @@ static int64_t WaitForInterruptDigital(HAL_InterruptHandle handle,
return WaitResult::Timeout;
}

interrupt->previousState = SimDIOData[digitalIndex].value;
interrupt->currentState = SimDIOData[digitalIndex].value;

int32_t uid = SimDIOData[digitalIndex].value.RegisterCallback(
&ProcessInterruptDigitalSynchronous,
Expand Down Expand Up @@ -252,14 +252,16 @@ static int64_t WaitForInterruptDigital(HAL_InterruptHandle handle,
if (timedOut) {
return WaitResult::Timeout;
}
// True => false, Falling
if (interrupt->previousState) {
// We know the value has changed because we would've timed out otherwise.
// If the current state is true, the previous state was false, so this is a
// rising edge. Otherwise, it's a falling edge.
if (interrupt->currentState) {
// Set our return value and our timestamps
interrupt->fallingTimestamp = hal::GetFPGATime();
return 1 << (8 + interrupt->index);
} else {
interrupt->risingTimestamp = hal::GetFPGATime();
return 1 << (interrupt->index);
} else {
interrupt->fallingTimestamp = hal::GetFPGATime();
return 1 << (8 + interrupt->index);
}
}

Expand All @@ -278,8 +280,8 @@ static int64_t WaitForInterruptAnalog(HAL_InterruptHandle handle,
data->interruptHandle = handle;

int32_t status = 0;
interrupt->previousState = GetAnalogTriggerValue(
interrupt->portHandle, interrupt->trigType, &status);
interrupt->currentState = GetAnalogTriggerValue(interrupt->portHandle,
interrupt->trigType, &status);

if (status != 0) {
return WaitResult::Timeout;
Expand Down Expand Up @@ -322,14 +324,16 @@ static int64_t WaitForInterruptAnalog(HAL_InterruptHandle handle,
if (timedOut) {
return WaitResult::Timeout;
}
// True => false, Falling
if (interrupt->previousState) {
// We know the value has changed because we would've timed out otherwise.
// If the current state is true, the previous state was false, so this is a
// rising edge. Otherwise, it's a falling edge.
if (interrupt->currentState) {
// Set our return value and our timestamps
interrupt->fallingTimestamp = hal::GetFPGATime();
return 1 << (8 + interrupt->index);
} else {
interrupt->risingTimestamp = hal::GetFPGATime();
return 1 << (interrupt->index);
} else {
interrupt->fallingTimestamp = hal::GetFPGATime();
return 1 << (8 + interrupt->index);
}
}

Expand Down
62 changes: 61 additions & 1 deletion wpilibc/src/test/native/cpp/InterruptTest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ TEST(InterruptTest, AsynchronousInterrupt) {
frc::Wait(0.5_s);
DIOSim digitalSim{di};
digitalSim.SetValue(false);
frc::Wait(20_ms);
frc::Wait(10_ms);
digitalSim.SetValue(true);
frc::Wait(10_ms);

Expand All @@ -42,4 +42,64 @@ TEST(InterruptTest, AsynchronousInterrupt) {
}
ASSERT_EQ(1, counter.load());
}

TEST(InterruptTest, RisingEdge) {
HAL_Initialize(500, 0);

std::atomic_bool hasFiredFallingEdge{false};
std::atomic_bool hasFiredRisingEdge{false};

DigitalInput di{0};
AsynchronousInterrupt interrupt{di, [&](bool rising, bool falling) {
hasFiredFallingEdge = falling;
hasFiredRisingEdge = rising;
}};
interrupt.SetInterruptEdges(true, true);
DIOSim digitalSim{di};
digitalSim.SetValue(false);
frc::Wait(0.5_s);
interrupt.Enable();
frc::Wait(10_ms);
digitalSim.SetValue(true);
frc::Wait(10_ms);

int count = 0;
while (!hasFiredRisingEdge) {
frc::Wait(5_ms);
count++;
ASSERT_TRUE(count < 1000);
}
EXPECT_FALSE(hasFiredFallingEdge);
EXPECT_TRUE(hasFiredRisingEdge);
}

TEST(InterruptTest, FallingEdge) {
HAL_Initialize(500, 0);

std::atomic_bool hasFiredFallingEdge{false};
std::atomic_bool hasFiredRisingEdge{false};

DigitalInput di{0};
AsynchronousInterrupt interrupt{di, [&](bool rising, bool falling) {
hasFiredFallingEdge = falling;
hasFiredRisingEdge = rising;
}};
interrupt.SetInterruptEdges(true, true);
DIOSim digitalSim{di};
digitalSim.SetValue(true);
frc::Wait(0.5_s);
interrupt.Enable();
frc::Wait(10_ms);
digitalSim.SetValue(false);
frc::Wait(10_ms);

int count = 0;
while (!hasFiredFallingEdge) {
frc::Wait(5_ms);
count++;
ASSERT_TRUE(count < 1000);
}
EXPECT_TRUE(hasFiredFallingEdge);
EXPECT_FALSE(hasFiredRisingEdge);
}
} // namespace frc
78 changes: 77 additions & 1 deletion wpilibj/src/test/java/edu/wpi/first/wpilibj/InterruptTest.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,9 @@

package edu.wpi.first.wpilibj;

import static org.junit.jupiter.api.Assertions.assertAll;
import static org.junit.jupiter.api.Assertions.assertEquals;
import static org.junit.jupiter.api.Assertions.assertFalse;
import static org.junit.jupiter.api.Assertions.assertTrue;

import edu.wpi.first.wpilibj.simulation.DIOSim;
Expand All @@ -22,7 +24,7 @@ void testAsynchronousInterrupt() {
AsynchronousInterrupt interrupt =
new AsynchronousInterrupt(
di,
(a, b) -> {
(rising, falling) -> {
counter.incrementAndGet();
hasFired.set(true);
})) {
Expand All @@ -43,4 +45,78 @@ void testAsynchronousInterrupt() {
assertEquals(1, counter.get(), "The interrupt did not fire the expected number of times");
}
}

@Test
void testRisingEdge() {
AtomicBoolean hasFiredFallingEdge = new AtomicBoolean(false);
AtomicBoolean hasFiredRisingEdge = new AtomicBoolean(false);

try (DigitalInput di = new DigitalInput(0);
AsynchronousInterrupt interrupt =
new AsynchronousInterrupt(
di,
(rising, falling) -> {
hasFiredFallingEdge.set(falling);
hasFiredRisingEdge.set(rising);
})) {
interrupt.setInterruptEdges(true, true);
DIOSim digitalSim = new DIOSim(di);
digitalSim.setValue(false);
Timer.delay(0.5);
interrupt.enable();
Timer.delay(0.01);
digitalSim.setValue(true);
Timer.delay(0.01);

int count = 0;
while (!hasFiredRisingEdge.get()) {
Timer.delay(0.005);
count++;
assertTrue(count < 1000);
}
assertAll(
() ->
assertFalse(hasFiredFallingEdge.get(), "The interrupt triggered on the falling edge"),
() ->
assertTrue(
hasFiredRisingEdge.get(), "The interrupt did not trigger on the rising edge"));
}
}

@Test
void testFallingEdge() {
AtomicBoolean hasFiredFallingEdge = new AtomicBoolean(false);
AtomicBoolean hasFiredRisingEdge = new AtomicBoolean(false);

try (DigitalInput di = new DigitalInput(0);
AsynchronousInterrupt interrupt =
new AsynchronousInterrupt(
di,
(rising, falling) -> {
hasFiredFallingEdge.set(falling);
hasFiredRisingEdge.set(rising);
})) {
interrupt.setInterruptEdges(true, true);
DIOSim digitalSim = new DIOSim(di);
digitalSim.setValue(true);
Timer.delay(0.5);
interrupt.enable();
Timer.delay(0.01);
digitalSim.setValue(false);
Timer.delay(0.01);

int count = 0;
while (!hasFiredFallingEdge.get()) {
Timer.delay(0.005);
count++;
assertTrue(count < 1000);
}
assertAll(
() ->
assertTrue(
hasFiredFallingEdge.get(), "The interrupt did not trigger on the rising edge"),
() ->
assertFalse(hasFiredRisingEdge.get(), "The interrupt triggered on the rising edge"));
}
}
}

0 comments on commit e5b7cf4

Please sign in to comment.