This repository was archived by the owner on Jul 25, 2022. It is now read-only.
File tree Expand file tree Collapse file tree 2 files changed +11
-3
lines changed Expand file tree Collapse file tree 2 files changed +11
-3
lines changed Original file line number Diff line number Diff line change @@ -26,17 +26,23 @@ class Drive
26
26
{
27
27
target = counter = 0 ;
28
28
pinMode (odoPin, INPUT);
29
- attachInterrupt (digitalPinToInterrupt (odoPin), evaluateInterval, FALLING );
29
+ attachInterrupt (digitalPinToInterrupt (odoPin), evaluateInterval, RISING );
30
30
31
31
analogWrite (motorControlpin, 0 );
32
32
pinMode (directionPin, OUTPUT);
33
33
}
34
34
35
35
IRAM_ATTR static void evaluateInterval ()
36
36
{
37
- if (++counter >= target)
37
+ const Milliseconds now = millis ();
38
+ static Milliseconds riseTime = now;
39
+ if (now - riseTime > board::odoMinIntervalDuration)
38
40
{
39
- stop ();
41
+ if (++counter >= target)
42
+ {
43
+ stop ();
44
+ }
45
+ riseTime = now;
40
46
}
41
47
}
42
48
Original file line number Diff line number Diff line change @@ -41,6 +41,8 @@ constexpr auto maxVelocity = 220; //!< [mm/s]
41
41
constexpr float odoIntervalLength = 12 *pi; // !< [mm]
42
42
// ! Minimum time with buffer factor [ms]
43
43
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)" );
44
46
};
45
47
46
48
#endif // BOARD_HPP
You can’t perform that action at this time.
0 commit comments