Skip to content

Commit fa34d17

Browse files
committed
MakerFaire
1 parent 6e9313d commit fa34d17

31 files changed

+1444
-817
lines changed

.github/workflows/TestCompile.yml

Lines changed: 11 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ jobs:
3232
- arduino:avr:uno
3333
- arduino:avr:uno|TimeOfFlight
3434
- arduino:avr:uno|BreadboardFull
35-
- arduino:avr:uno|Mecanum
35+
# - arduino:avr:uno|Mecanum
3636

3737
include:
3838
- arduino-boards-fqbn: arduino:avr:uno
@@ -41,7 +41,7 @@ jobs:
4141
-DBLUETOOTH_BAUD_RATE=BAUD_115200
4242
-DUS_SENSOR_SUPPORTS_1_PIN_MODE
4343
-DDISTANCE_SERVO_IS_MOUNTED_HEAD_DOWN
44-
-DUSE_ADAFRUIT_MOTOR_SHIELD
44+
-mcall-prologues # reduces size by 870 bytes
4545

4646
- arduino-boards-fqbn: arduino:avr:uno|TimeOfFlight # UNO board with ToF distance sensor
4747
build-properties:
@@ -59,14 +59,16 @@ jobs:
5959
-DUS_SENSOR_SUPPORTS_1_PIN_MODE
6060
-mcall-prologues # reduces size by 870 bytes
6161

62-
- arduino-boards-fqbn: arduino:avr:uno|Mecanum # Nano board with TB6612 breakout board + 4 mecanum wheels
63-
build-properties:
64-
RobotCarBlueDisplay:
65-
-DMECANUM_BASIC_CONFIGURATION
66-
-DBLUETOOTH_BAUD_RATE=BAUD_115200
67-
-DUS_SENSOR_SUPPORTS_1_PIN_MODE
68-
-mcall-prologues # reduces size by 870 bytes
62+
# - arduino-boards-fqbn: arduino:avr:uno|Mecanum # Nano board with TB6612 breakout board + 4 mecanum wheels
63+
# build-properties:
64+
# RobotCarBlueDisplay:
65+
# -DMECANUM_BASIC_CONFIGURATION
66+
# -DBLUETOOTH_BAUD_RATE=BAUD_115200
67+
# -DUS_SENSOR_SUPPORTS_1_PIN_MODE
68+
# -mcall-prologues # reduces size by 870 bytes
6969

70+
# Do not cancel all jobs / architectures if one job fails
71+
fail-fast: false
7072

7173
steps:
7274
- name: Checkout

README.md

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -20,17 +20,19 @@ the **[BlueDisplay library](https://github.com/ArminJo/BlueDisplay)** for Smartp
2020
| 4WD car with IR receiver and Bluetooth module and 4 AA rechargeable batteries. | Instructable |
2121
|-|-|
2222
| ![4 wheel car](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/4WDInstructable.jpg) | [![Instructable](https://github.com/ArminJo/Arduino-OpenWindowAlarm/blob/master/pictures/instructables-logo-v2.png)](https://www.instructables.com/Arduino-4WD-Car-Assembly-and-Code-With-Optional-In/) |
23-
| 4 wheel car, like 2 WD car before, but with servo mounted head up. | 2 wheel car with encoders, 2 Li-ion batteries, Adafruit Motor Shield V2, Bluetooth connection, and servo mounted head down. |
23+
| 4 wheel car like the 2 WD car right, but with servo mounted head up. | 2 wheel car with encoders, 2 Li-ion batteries, Adafruit Motor Shield V2, Bluetooth connection, and servo mounted head down. |
2424
| ![4 wheel car](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/4WheelDriveCar.jpg) | ![2 wheel car](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/2WheelDriveCar.jpg) |
2525
| Encoder fork sensor | Servo mounted head down |
2626
| ![Encoder fork sensor](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/ForkSensor.jpg) | ![Servo mounting](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/ServoAtTopBack.jpg) |
27-
| VIN sensing | |
28-
| ![VIN sensing](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/SensingVIn.jpg) | |
27+
| VIN sensing with motor shield | Red car with Sharp GP2Y0A21YK distance sensor |
28+
| ![VIN sensing](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/SensingVIn.jpg) | https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/RedCar.jpg |
2929

3030
# SCREENSHOTS
3131
| Start page | Test page |
3232
|-|-|
3333
| ![Start page](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/HomePage.png) | ![Test page](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/TestPage.png) |
34+
| Sensor drive page | Sensor drive page for mecanum car |
35+
| ![Sensor drive page](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/SensorDrivePage.jpg) | ![Sensor drive page for mecanum car](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/SensorDrivePageWithTurn.jpg) |
3436

3537
Automatic control page with detected wall at right
3638
![Automatic control page](https://github.com/ArminJo/Arduino-RobotCar/blob/master/pictures/AutoDrivePageWallDetected.jpg)
@@ -56,10 +58,10 @@ Compile options for the used **PWMMotorControl library** like `USE_ENCODER_MOTOR
5658

5759
| Name | Default value | Description |
5860
|-|-|-|
59-
| `CAR_HAS_VIN_VOLTAGE_DIVIDER` | undefined | VIN/11 at A2, e.g. 1MOhm to VIN, 100kOhm to ground. Required to show and monitor (for undervoltage) VIN voltage. |
61+
| `CAR_HAS_VIN_VOLTAGE_DIVIDER` | undefined | VIN/11 at A2, e.g. 1 MΩ to VIN, 100 kΩ to ground. Required to show and monitor (for undervoltage) VIN voltage. |
6062
| `VIN_VOLTAGE_CORRECTION` | undefined or 0.8 for UNO | Voltage to be subtracted from VIN voltage for voltage monitoring. E.g. if there is a series diode between Li-ion and VIN as on the UNO boards, set it to 0.8. |
6163
| `CAR_HAS_US_DISTANCE_SENSOR` | disabled | A HC-SR04 ultrasonic distance sensor is mounted (default for most China smart cars). |
62-
| `US_SENSOR_SUPPORTS_1_PIN_MODE` | disabled | Use modified HC-SR04 modules or HY-SRF05 ones.</br>Modify HC-SR04 by connecting 10kOhm between echo and trigger and then use only trigger pin. |
64+
| `US_SENSOR_SUPPORTS_1_PIN_MODE` | disabled | Use modified HC-SR04 modules or HY-SRF05 ones.</br>Modify HC-SR04 by connecting 10 k&ohm; between echo and trigger and then use only trigger pin. |
6365
| `CAR_HAS_IR_DISTANCE_SENSOR` | disabled | Use Sharp GP2Y0A21YK / 1080 IR distance sensor. |
6466
| `CAR_HAS_TOF_DISTANCE_SENSOR` | disabled | Use VL53L1X TimeOfFlight distance sensor. |
6567
| `CAR_HAS_DISTANCE_SERVO` | disabled | Distance sensor is mounted on a pan servo (default for most China smart cars). |
@@ -69,8 +71,8 @@ Compile options for the used **PWMMotorControl library** like `USE_ENCODER_MOTOR
6971
| `CAR_HAS_CAMERA` | disabled | Enables the `Camera` button for the `PIN_CAMERA_SUPPLY_CONTROL` pin. |
7072
| `CAR_HAS_LASER` | disabled | Enables the `Laser` button for the `PIN_LASER_OUT` / `LED_BUILTIN` pin. |
7173
| `ENABLE_RTTTL_FOR_CAR` | undefined | Plays melody after initial timeout has reached. Enables the Melody button, which plays a random melody. |
72-
| `MONITOR_VIN_VOLTAGE` | disabled | Shows VIN voltage and monitors it for undervoltage. VIN/11 at A2, 1MOhm to VIN, 100kOhm to ground. |
73-
| `ENABLE_EEPROM_STORAGE` | disabled | Activates the buttons to store compensation and drive speed. |
74+
| `MONITOR_VIN_VOLTAGE` | disabled | Shows VIN voltage and monitors it for undervoltage. VIN/11 at A2, 1 M&ohm; to VIN, 100 k&ohm; to ground. |
75+
| `ENABLE_EEPROM_STORAGE` | disabled | Activates the buttons to store compensation values. Normally they are stored after calibration. |
7476

7577
### Changing include (*.h) files with Arduino IDE
7678
First, use *Sketch > Show Sketch Folder (Ctrl+K)*.<br/>
200 KB
Binary file not shown.

pictures/RedCar.jpg

1.56 MB
Loading

pictures/SensorDrivePage.jpg

87.1 KB
Loading

pictures/SensorDrivePageWithTurn.jpg

133 KB
Loading

src/ADCUtils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@
3434
* with INTERNAL you can calibrate your ADC readout. For my Nanos I measured e.g. 1060 mV and 1093 mV.
3535
*/
3636
#if !defined(ADC_INTERNAL_REFERENCE_MILLIVOLT)
37-
#define ADC_INTERNAL_REFERENCE_MILLIVOLT 1100L // Value measured at the AREF pin
37+
#define ADC_INTERNAL_REFERENCE_MILLIVOLT 1100L // Value measured at the AREF pin. If value > real AREF voltage, measured values are > real values
3838
#endif
3939

4040
// Union to speed up the combination of low and high bytes to a word

src/AutonomousDrive.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -101,7 +101,7 @@ void startStopAutomomousDrive(bool aDoStart, uint8_t aDriveMode) {
101101
#if defined(ENABLE_PATH_INFO_PAGE)
102102
if (sStepMode != MODE_SINGLE_STEP) {
103103
// add last driven distance to path
104-
insertToPath(RobotCar.rightCarMotor.LastRideEncoderCount, sLastDegreesTurned, true);
104+
insertToPath(RobotCar.rightCarMotor.EncoderCount, sLastDegreesTurned, true);
105105
}
106106
#endif
107107
DistanceServoWriteAndDelay(90);
@@ -237,7 +237,7 @@ void driveCollisonAvoidingOneStep() {
237237
insertToPath(CENTIMETER_PER_RIDE * 2, sLastDegreesTurned, true);
238238
} else {
239239
// add last driven distance to path
240-
insertToPath(RobotCar.rightCarMotor.LastRideEncoderCount, sLastDegreesTurned, true);
240+
insertToPath(RobotCar.rightCarMotor.EncoderCount, sLastDegreesTurned, true);
241241
}
242242
} else {
243243
/*

src/AutonomousDrivePage.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -286,8 +286,8 @@ void startAutonomousDrivePage(void) {
286286
SliderIROrTofDistance.setPosition(POS_X_DISTANCE_POSITION_SLIDER - (TEXT_SIZE_11_WIDTH + BUTTON_WIDTH_10), SLIDER_SHIFTED_Y_POS);
287287
#endif
288288
drawAutonomousDrivePage();
289-
if(!isCalibrated) {
290-
calibrateAndPrint();
289+
if(!isPWMCalibrated) {
290+
calibrateDriveSpeedPWMAndPrint();
291291
}
292292
}
293293

src/BTSensorDrivePage.hpp

Lines changed: 69 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -51,8 +51,8 @@ uint8_t sSensorChangeCallCountForZeroAdjustment;
5151
float sYZeroValueAdded; // The accumulator for the values of the first 8 calls.
5252
float sYZeroValue = 0;
5353

54-
struct positiveNegativeSlider sAccelerationLeftRightSliders;
55-
struct positiveNegativeSlider sAccelerationForwardBackwardSliders;
54+
struct positiveNegativeSlider sAccelerationLeftRightSliders; // Left is positive slider
55+
struct positiveNegativeSlider sAccelerationForwardBackwardSliders; // Forward is positive slider
5656

5757
#if defined(CAR_HAS_4_MECANUM_WHEELS)
5858
BDButton TouchButtonTurnMode;
@@ -116,20 +116,80 @@ void doSensorChange(uint8_t aSensorType, struct SensorCallback *aSensorCallbackI
116116
BlueDisplay1.playTone(24); // feedback for zero value acquired
117117
} else {
118118

119+
#if defined(CAR_HAS_4_MECANUM_WHEELS)
119120
/*
120121
* Regular operation here
122+
* Forward backward handling
123+
* We operate with speed and direction instead of signed speed, because direction postprocessing is easier then
124+
*/
125+
int tForwardBackwardValue = -((aSensorCallbackInfo->ValueY - sYZeroValue) * (MAX_SPEED_PWM / 10)); // Scale value to 0 to MAX_SPEED_PWM
126+
uint8_t tDirection = DIRECTION_FORWARD;
127+
bool tDirectionForward = true;
128+
if (tForwardBackwardValue < 0) {
129+
tDirection = DIRECTION_BACKWARD;
130+
tDirectionForward = false;
131+
tForwardBackwardValue = -tForwardBackwardValue;
132+
}
133+
tForwardBackwardValue = setPositiveNegativeSliders(&sAccelerationForwardBackwardSliders, (unsigned int)tForwardBackwardValue,
134+
tDirectionForward, SPEED_DEAD_BAND);
135+
136+
//Print speedPWM as value of bottom slider
137+
sprintf(sStringBuffer, "%3d", tForwardBackwardValue);
138+
SliderBackward.printValue(sStringBuffer);
139+
140+
/*
121141
* Left right handling
122142
*/
143+
int tLeftRightValue = aSensorCallbackInfo->ValueX * (MAX_SPEED_PWM / 10); // Scale value
144+
bool tDirectionLeft = true;
145+
if (tLeftRightValue < 0) {
146+
tDirection |= DIRECTION_RIGHT;
147+
tDirectionLeft = false;
148+
tLeftRightValue = -tLeftRightValue;
149+
} else if (tLeftRightValue > 0) {
150+
tDirection |= DIRECTION_LEFT;
151+
}
152+
tLeftRightValue = setPositiveNegativeSliders(&sAccelerationLeftRightSliders, (unsigned int)tLeftRightValue, tDirectionLeft, SPEED_DEAD_BAND);
153+
154+
/*
155+
* Direction postprocessing
156+
*/
157+
if (tForwardBackwardValue == 0 && tLeftRightValue == 0) {
158+
tDirection = DIRECTION_STOP;
159+
}
160+
if(tLeftRightValue == 0 || tForwardBackwardValue > 2 * tLeftRightValue) {
161+
//suppress left right
162+
tDirection &= ~DIRECTION_LEFT_RIGHT_MASK;
163+
}
164+
if (tForwardBackwardValue == 0 || tLeftRightValue > 2 * tForwardBackwardValue) {
165+
//suppress forward backward
166+
tDirection &= ~DIRECTION_FORWARD_BACKWARD_MASK;
167+
}
168+
if(sTurnModeEnabled) {
169+
tDirection |= DIRECTION_TURN;
170+
}
171+
172+
unsigned int tSpeedPWM = max(tForwardBackwardValue, tLeftRightValue);
173+
// reapply dead band;
174+
tSpeedPWM += SPEED_DEAD_BAND;
175+
// overflow handling since analogWrite only accepts byte values
176+
if (tSpeedPWM > MAX_SPEED_PWM) {
177+
tSpeedPWM = MAX_SPEED_PWM;
178+
}
179+
RobotCar.setSpeedPWMAndDirection(tSpeedPWM, tDirection);
180+
#else //defined(CAR_HAS_4_MECANUM_WHEELS)
181+
182+
/*
183+
* Regular operation here
184+
* Left right handling
185+
* We operate with signed speed, because speed for left and right motors can be computed easier
186+
*/
123187
#if defined(CAR_HAS_4_WHEELS)
124188
int tLeftRightValue = aSensorCallbackInfo->ValueX * 16.0;
125189
#else
126190
int tLeftRightValue = aSensorCallbackInfo->ValueX * 8.0; // Scale value
127191
#endif
128-
#if defined(CAR_HAS_4_MECANUM_WHEELS)
129-
tLeftRightValue = setPositiveNegativeSliders(&sAccelerationLeftRightSliders, tLeftRightValue, SPEED_DEAD_BAND);
130-
#else
131192
tLeftRightValue = setPositiveNegativeSliders(&sAccelerationLeftRightSliders, tLeftRightValue, LEFT_RIGHT_SENSOR_DEAD_BAND);
132-
#endif
133193
/*
134194
* forward backward handling
135195
*/
@@ -141,38 +201,11 @@ void doSensorChange(uint8_t aSensorType, struct SensorCallback *aSensorCallbackI
141201
*/
142202
sprintf(sStringBuffer, "%4d", tSpeedPWMValue);
143203
SliderBackward.printValue(sStringBuffer);
144-
145-
#if defined(CAR_HAS_4_MECANUM_WHEELS)
146-
/*
147-
* Get direction
148-
*/
149-
uint8_t tDirection = DIRECTION_STOP;
150-
if(tSpeedPWMValue > 0) {
151-
tDirection = DIRECTION_FORWARD;
152-
} else if (tSpeedPWMValue < 0) {
153-
tSpeedPWMValue = -tSpeedPWMValue;
154-
tDirection = DIRECTION_BACKWARD;
155-
}
156-
if(tLeftRightValue > 0) {
157-
// Left
158-
tDirection |= DIRECTION_LEFT;
159-
} else if(tLeftRightValue < 0) {
160-
tLeftRightValue = - tLeftRightValue;
161-
tDirection |= DIRECTION_RIGHT;
162-
}
163-
if(sTurnModeEnabled) {
164-
tDirection |= DIRECTION_TURN;
165-
}
166-
tSpeedPWMValue = max(tSpeedPWMValue, tLeftRightValue);
167-
RobotCar.setSpeedPWMAndDirection(speedOverflowAndDeadBandHandling(tSpeedPWMValue), tDirection);
168-
#else
169-
if(tSpeedPWMValue < 0){
204+
if (tSpeedPWMValue < 0) {
170205
tLeftRightValue = -tLeftRightValue;
171206
}
172-
RobotCar.rightCarMotor.setSpeedPWMAndDirection(
173-
speedOverflowAndDeadBandHandling(tSpeedPWMValue + tLeftRightValue));
174-
RobotCar.leftCarMotor.setSpeedPWMAndDirection(
175-
speedOverflowAndDeadBandHandling(tSpeedPWMValue - tLeftRightValue));
207+
RobotCar.rightCarMotor.setSpeedPWMAndDirection(speedOverflowAndDeadBandHandling(tSpeedPWMValue + tLeftRightValue));
208+
RobotCar.leftCarMotor.setSpeedPWMAndDirection(speedOverflowAndDeadBandHandling(tSpeedPWMValue - tLeftRightValue));
176209
#endif
177210
}
178211
}

0 commit comments

Comments
 (0)