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

Commit 1ad9f7f

Browse files
committed
Adjusted odometry and tuned drives.
2 parents f6d1783 + 68d5985 commit 1ad9f7f

File tree

3 files changed

+31
-8
lines changed

3 files changed

+31
-8
lines changed

robot-control-src/Drives.cpp

Lines changed: 7 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -33,16 +33,18 @@ bool Drive<MOTORCONTROL, motorControlpin, DIRECTIONPIN, directionPin, ODOPIN, od
3333
* cycle of the right motor control.
3434
*
3535
* The calibration fraction is defined as follows: It has been observed, that when the
36-
* duty cycle of the left is 350/1023, then the right should be 325/1023 in order for the
36+
* duty cycle of the left is x/1023, then the right should be y/1023 in order for the
3737
* drives to be equally fast. The linear functions is such that the difference is 0 with
3838
* a duty cycle of 100%.
3939
*/
4040
static Amplitude calcRightSpeed(const Amplitude leftSpeed)
4141
{
42-
constexpr double calibrationFraction = 25.0 / (maxAmplitude - 350.0);
43-
constexpr float a = 1.0 + calibrationFraction;
44-
constexpr float b = maxAmplitude * calibrationFraction;
45-
return a*leftSpeed - b;
42+
constexpr Amplitude leftAmplitude = 350; // x
43+
constexpr Amplitude rightMatchingAmplitude = 290; // y
44+
constexpr double calibrationFraction = (leftAmplitude
45+
- rightMatchingAmplitude)
46+
/ static_cast<double>(maxAmplitude - leftAmplitude);
47+
return leftSpeed - calibrationFraction * (maxAmplitude - leftSpeed);
4648
}
4749

4850
void rotateCounter(const Counter steps, const Amplitude amplitude, bool const clockwise)

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: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,8 +26,23 @@ extern MCP23017Pin rightBackwards;
2626
extern MCP23017Pin leftBumper;
2727
extern MCP23017Pin rightBumper;
2828

29+
/**
30+
* Maximum robot velocity.
31+
*
32+
* According to [this wiki](https://rn-wissen.de/wiki/index.php/CCRP5#Technische_Daten).
33+
*/
2934
constexpr auto maxVelocity = 220; //!< [mm/s]
35+
/**
36+
* distance of one outer wheel turn U = d*pi
37+
* diameter of outer wheel d = 50 mm
38+
* fraction of one odometry interval to outer wheel f = 6/25
39+
* distance of one odometry interval = f*U
40+
*/
3041
constexpr float odoIntervalLength = 12*pi; //!< [mm]
42+
//! Minimum time with buffer factor [ms]
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)");
3146
};
3247

3348
#endif // BOARD_HPP

0 commit comments

Comments
 (0)