Skip to content
This repository was archived by the owner on Jul 25, 2022. It is now read-only.

Commit afd0dad

Browse files
committed
Added threshold to odometry counter.
In order to suppress bouncing.
1 parent 8038576 commit afd0dad

File tree

2 files changed

+11
-3
lines changed

2 files changed

+11
-3
lines changed

robot-control-src/Drives.hpp

Lines changed: 9 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,17 +26,23 @@ class Drive
2626
{
2727
target = counter = 0;
2828
pinMode(odoPin, INPUT);
29-
attachInterrupt(digitalPinToInterrupt(odoPin), evaluateInterval, FALLING);
29+
attachInterrupt(digitalPinToInterrupt(odoPin), evaluateInterval, RISING);
3030

3131
analogWrite(motorControlpin, 0);
3232
pinMode(directionPin, OUTPUT);
3333
}
3434

3535
IRAM_ATTR static void evaluateInterval()
3636
{
37-
if (++counter >= target)
37+
const Milliseconds now = millis();
38+
static Milliseconds riseTime = now;
39+
if(now - riseTime > board::odoMinIntervalDuration)
3840
{
39-
stop();
41+
if (++counter >= target)
42+
{
43+
stop();
44+
}
45+
riseTime = now;
4046
}
4147
}
4248

robot-control-src/board.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -41,6 +41,8 @@ constexpr auto maxVelocity = 220; //!< [mm/s]
4141
constexpr float odoIntervalLength = 12*pi; //!< [mm]
4242
//! Minimum time with buffer factor [ms]
4343
constexpr Milliseconds odoMinIntervalDuration = (odoIntervalLength * 1000.0) / (maxVelocity*2.0);
44+
static_assert(odoMinIntervalDuration > 38, "threshold must be greater than longest pulse of photoelectric sensor (measured at slowest speed)");
45+
static_assert(odoMinIntervalDuration < 142, "threshold must be smaller than shortest odometry interval between pulses (measured at highest speed)");
4446
};
4547

4648
#endif // BOARD_HPP

0 commit comments

Comments
 (0)