Skip to content

Commit

Permalink
Housekeeping
Browse files Browse the repository at this point in the history
  • Loading branch information
ArminJo committed Oct 8, 2024
1 parent 933b3e6 commit 2c23c53
Show file tree
Hide file tree
Showing 60 changed files with 959 additions and 395 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@ Contains the [RobotCarBlueDisplay](https://github.com/ArminJo/Arduino-RobotCar)
   
[![Button API](https://img.shields.io/badge/API-yellow?logoColor=white&logo=OpenStreetMap)](https://github.com/ArminJo/PWMMotorControl#api)
   
[![Button Changelog](https://img.shields.io/badge/Changelog-blue?logoColor=white&logo=AzureArtifacts)](https://github.com/ArminJo/PWMMotorControl#revision-history)
[![Button Changelog](https://img.shields.io/badge/Changelog-blue?logoColor=white&logo=AzureArtifacts)](https://github.com/ArminJo/PWMMotorControl?tab=readme-ov-file#revision-history)

</div>

Expand Down
15 changes: 1 addition & 14 deletions examples/Basic/RobotCarPinDefinitionsAndMore.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,20 +235,7 @@
# if !defined(LED_BUILTIN) && !defined(CAR_IS_ESP32_CAM_BASED)
#define LED_BUILTIN PB1
# endif
#define TONE_LEDC_CHANNEL 1 // Using channel 1 makes tone() independent of receiving timer -> No need to stop receiving timer.
void tone(uint8_t _pin, unsigned int frequency){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
}
void tone(uint8_t _pin, unsigned int frequency, unsigned long duration){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
delay(duration);
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}
void noTone(uint8_t _pin){
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}

#else // NANO_BASED
// Uno based
// Pin A0 for VCC monitoring - ADC channel 2
Expand Down
20 changes: 18 additions & 2 deletions examples/BasicDistance/ADCUtils.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,27 +85,39 @@
#define ADC_TEMPERATURE_CHANNEL_MUX 15
#define ADC_1_1_VOLT_CHANNEL_MUX 12
#define ADC_GND_CHANNEL_MUX 13
#define ADC_CHANNEL_MUX_MASK 0x0F

#elif defined(__AVR_ATtiny87__) || defined(__AVR_ATtiny167__)
#define ADC_ISCR_CHANNEL_MUX 3
#define ADC_TEMPERATURE_CHANNEL_MUX 11
#define ADC_1_1_VOLT_CHANNEL_MUX 12
#define ADC_GND_CHANNEL_MUX 14
#define ADC_VCC_4TH_CHANNEL_MUX 13
#define ADC_CHANNEL_MUX_MASK 0x1F

#elif defined(__AVR_ATmega328P__)
#define ADC_TEMPERATURE_CHANNEL_MUX 8
#define ADC_1_1_VOLT_CHANNEL_MUX 14
#define ADC_GND_CHANNEL_MUX 15
#define ADC_CHANNEL_MUX_MASK 0x0F

#elif defined(__AVR_ATmega644P__)
#define ADC_TEMPERATURE_CHANNEL_MUX // not existent
#define ADC_1_1_VOLT_CHANNEL_MUX 0x1E
#define ADC_GND_CHANNEL_MUX 0x1F
#define ADC_CHANNEL_MUX_MASK 0x0F

#elif defined(__AVR_ATmega32U4__)
#define ADC_TEMPERATURE_CHANNEL_MUX 0x27
#define ADC_1_1_VOLT_CHANNEL_MUX 0x1E
#define ADC_GND_CHANNEL_MUX 0x1F
#define ADC_CHANNEL_MUX_MASK 0x3F

#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1284__) || defined(__AVR_ATmega1284P__) || defined(__AVR_ATmega644__) || defined(__AVR_ATmega644A__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__)
#define ADC_1_1_VOLT_CHANNEL_MUX 0x1E
#define ADC_GND_CHANNEL_MUX 0x1F
#define ADC_CHANNEL_MUX_MASK 0x1F

#define INTERNAL INTERNAL1V1

#else
Expand Down Expand Up @@ -164,7 +176,10 @@ uint16_t waitAndReadADCChannelWithReferenceAndRestoreADMUXAndReference(uint8_t a
uint16_t readADCChannelWithOversample(uint8_t aADCChannelNumber, uint8_t aOversampleExponent);
void setADCChannelAndReferenceForNextConversion(uint8_t aADCChannelNumber, uint8_t aReference);
uint16_t readADCChannelWithReferenceOversampleFast(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aOversampleExponent);
uint16_t readADCChannelWithReferenceMultiSamples(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aNumberOfSamples);
uint32_t readADCChannelMultiSamples(uint8_t aPrescale, uint16_t aNumberOfSamples);
uint16_t readADCChannelMultiSamplesWithReference(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aNumberOfSamples);
uint32_t readADCChannelMultiSamplesWithReferenceAndPrescaler(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aPrescale,
uint16_t aNumberOfSamples);
uint16_t readADCChannelWithReferenceMax(uint8_t aADCChannelNumber, uint8_t aReference, uint16_t aNumberOfSamples);
uint16_t readADCChannelWithReferenceMaxMicros(uint8_t aADCChannelNumber, uint8_t aReference, uint16_t aMicrosecondsToAquire);
uint16_t readUntil4ConsecutiveValuesAreEqual(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aDelay,
Expand Down Expand Up @@ -199,7 +214,8 @@ void resetCounterForVCCUndervoltageMultipleTimes();
bool isVCCUndervoltage();
bool isVCCEmergencyUndervoltage();
bool isVCCOvervoltage();
bool isVCCOvervoltageSimple();
bool isVCCOvervoltageSimple(); // Version using readVCCVoltageMillivoltSimple()
bool isVCCTooHighSimple(); // Version not using readVCCVoltageMillivoltSimple()

#endif // defined(__AVR__) ...

Expand Down
115 changes: 100 additions & 15 deletions examples/BasicDistance/ADCUtils.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -161,12 +161,15 @@ uint8_t checkAndWaitForReferenceAndChannelToSwitch(uint8_t aADCChannelNumber, ui
if ((tOldADMUX & MASK_FOR_ADC_REFERENCE) != tNewReference && (aReference == INTERNAL || aReference == INTERNAL2V56)) {
#else
if ((tOldADMUX & MASK_FOR_ADC_REFERENCE) != tNewReference && aReference == INTERNAL) {
#endif
#if defined(LOCAL_DEBUG)
Serial.println(F("Switch from DEFAULT to INTERNAL"));
#endif
/*
* Switch reference from DEFAULT to INTERNAL
*/
delayMicroseconds(8000); // experimental value is >= 7600 us for Nano board and 6200 for Uno board
} else if ((tOldADMUX & 0x0F) != aADCChannelNumber) {
} else if ((tOldADMUX & ADC_CHANNEL_MUX_MASK) != aADCChannelNumber) {
if (aADCChannelNumber == ADC_1_1_VOLT_CHANNEL_MUX) {
/*
* Internal 1.1 Volt channel requires <= 200 us for Nano board
Expand Down Expand Up @@ -249,9 +252,10 @@ uint16_t readADCChannelWithReferenceOversampleFast(uint8_t aADCChannelNumber, ui

/*
* Returns sum of all sample values
* Conversion time is defined as 0.104 milliseconds for 16 MHz Arduino by ADC_PRESCALE in ADCUtils.h.
* Conversion time is defined as 0.104 milliseconds for 16 MHz Arduino by ADC_PRESCALE (=ADC_PRESCALE128) in ADCUtils.h.
* @ param aNumberOfSamples If > 64 an overflow may occur.
*/
uint16_t readADCChannelWithReferenceMultiSamples(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aNumberOfSamples) {
uint16_t readADCChannelMultiSamplesWithReference(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aNumberOfSamples) {
uint16_t tSumValue = 0;
ADMUX = aADCChannelNumber | (aReference << SHIFT_VALUE_FOR_REFERENCE);

Expand All @@ -275,6 +279,65 @@ uint16_t readADCChannelWithReferenceMultiSamples(uint8_t aADCChannelNumber, uint
return tSumValue;
}

/*
* Returns sum of all sample values
* Conversion time is defined as 0.104 milliseconds for 16 MHz Arduino for ADC_PRESCALE128 in ADCUtils.h.
* @ param aPrescale can be one of ADC_PRESCALE2, ADC_PRESCALE4, 8, 16, 32, 64, 128.
* ADC_PRESCALE32 is recommended for excellent linearity and fast readout of 26 microseconds
* @ param aNumberOfSamples If > 16k an overflow may occur.
*/
uint32_t readADCChannelMultiSamplesWithReferenceAndPrescaler(uint8_t aADCChannelNumber, uint8_t aReference, uint8_t aPrescale,
uint16_t aNumberOfSamples) {
uint32_t tSumValue = 0;
ADMUX = aADCChannelNumber | (aReference << SHIFT_VALUE_FOR_REFERENCE);

ADCSRB = 0; // Free running mode. Only active if ADATE is set to 1.
// ADSC-StartConversion ADATE-AutoTriggerEnable ADIF-Reset Interrupt Flag
ADCSRA = (_BV(ADEN) | _BV(ADSC) | _BV(ADATE) | _BV(ADIF) | aPrescale);

for (uint16_t i = 0; i < aNumberOfSamples; i++) {
/*
* wait for free running conversion to finish.
* Do not wait for ADSC here, since ADSC is only low for 1 ADC Clock cycle on free running conversion.
*/
loop_until_bit_is_set(ADCSRA, ADIF);

ADCSRA |= _BV(ADIF); // clear bit to enable recognizing next conversion has finished
// Add value
tSumValue += ADCL | (ADCH << 8); // using WordUnionForADCUtils does not save space here
// tSumValue += (ADCH << 8) | ADCL; // this does NOT work!
}
ADCSRA &= ~_BV(ADATE); // Disable auto-triggering (free running mode)
return tSumValue;
}

/*
* Returns sum of all sample values
* Assumes, that channel and reference are still set to the right values
* @ param aNumberOfSamples If > 16k an overflow may occur.
*/
uint32_t readADCChannelMultiSamples(uint8_t aPrescale, uint16_t aNumberOfSamples) {
uint32_t tSumValue = 0;

ADCSRB = 0; // Free running mode. Only active if ADATE is set to 1.
// ADSC-StartConversion ADATE-AutoTriggerEnable ADIF-Reset Interrupt Flag
ADCSRA = (_BV(ADEN) | _BV(ADSC) | _BV(ADATE) | _BV(ADIF) | aPrescale);

for (uint16_t i = 0; i < aNumberOfSamples; i++) {
/*
* wait for free running conversion to finish.
* Do not wait for ADSC here, since ADSC is only low for 1 ADC Clock cycle on free running conversion.
*/
loop_until_bit_is_set(ADCSRA, ADIF);

ADCSRA |= _BV(ADIF); // clear bit to enable recognizing next conversion has finished
// Add value
tSumValue += ADCL | (ADCH << 8); // using WordUnionForADCUtils does not save space here
// tSumValue += (ADCH << 8) | ADCL; // this does NOT work!
}
ADCSRA &= ~_BV(ADATE); // Disable auto-triggering (free running mode)
return tSumValue;
}
/*
* use ADC_PRESCALE32 which gives 26 us conversion time and good linearity
* @return the maximum value of aNumberOfSamples samples.
Expand Down Expand Up @@ -408,7 +471,7 @@ uint16_t readUntil4ConsecutiveValuesAreEqual(uint8_t aADCChannelNumber, uint8_t
*/
float getVCCVoltageSimple(void) {
// use AVCC with (optional) external capacitor at AREF pin as reference
float tVCC = readADCChannelWithReferenceMultiSamples(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
float tVCC = readADCChannelMultiSamplesWithReference(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
return ((1023 * 1.1 * 4) / tVCC);
}

Expand All @@ -419,7 +482,7 @@ float getVCCVoltageSimple(void) {
*/
uint16_t getVCCVoltageMillivoltSimple(void) {
// use AVCC with external capacitor at AREF pin as reference
uint16_t tVCC = readADCChannelWithReferenceMultiSamples(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
uint16_t tVCC = readADCChannelMultiSamplesWithReference(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
return ((1023L * ADC_INTERNAL_REFERENCE_MILLIVOLT * 4) / tVCC);
}

Expand Down Expand Up @@ -459,6 +522,9 @@ uint16_t getVCCVoltageMillivolt(void) {
return ((1023L * ADC_INTERNAL_REFERENCE_MILLIVOLT) / tVCC);
}

/*
* Does not set sVCCVoltageMillivolt
*/
uint16_t printVCCVoltageMillivolt(Print *aSerial) {
aSerial->print(F("VCC="));
uint16_t tVCCVoltageMillivolt = getVCCVoltageMillivolt();
Expand All @@ -480,7 +546,7 @@ void readAndPrintVCCVoltageMillivolt(Print *aSerial) {
*/
void readVCCVoltageSimple(void) {
// use AVCC with (optional) external capacitor at AREF pin as reference
float tVCC = readADCChannelWithReferenceMultiSamples(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
float tVCC = readADCChannelMultiSamplesWithReference(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
sVCCVoltage = (1023 * (((float) ADC_INTERNAL_REFERENCE_MILLIVOLT) / 1000) * 4) / tVCC;
}

Expand All @@ -491,7 +557,7 @@ void readVCCVoltageSimple(void) {
*/
void readVCCVoltageMillivoltSimple(void) {
// use AVCC with external capacitor at AREF pin as reference
uint16_t tVCCVoltageMillivoltRaw = readADCChannelWithReferenceMultiSamples(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
uint16_t tVCCVoltageMillivoltRaw = readADCChannelMultiSamplesWithReference(ADC_1_1_VOLT_CHANNEL_MUX, DEFAULT, 4);
sVCCVoltageMillivolt = (1023L * ADC_INTERNAL_REFERENCE_MILLIVOLT * 4) / tVCCVoltageMillivoltRaw;
}

Expand Down Expand Up @@ -556,7 +622,7 @@ bool isVCCUSBPowered(Print *aSerial) {
aSerial->print(F("USB powered is "));
bool tReturnValue;
if (VOLTAGE_USB_POWERED_LOWER_THRESHOLD_MILLIVOLT
< sVCCVoltageMillivolt && sVCCVoltageMillivolt < VOLTAGE_USB_POWERED_UPPER_THRESHOLD_MILLIVOLT) {
< sVCCVoltageMillivolt&& sVCCVoltageMillivolt < VOLTAGE_USB_POWERED_UPPER_THRESHOLD_MILLIVOLT) {
tReturnValue = true;
aSerial->print(F("true "));
} else {
Expand Down Expand Up @@ -649,6 +715,7 @@ void resetCounterForVCCUndervoltageMultipleTimes() {
* Raw reading of 1.1 V is 221 at 5.1 V.
* Raw reading of 1.1 V is 214 at 5.25 V (+5 %).
* Raw reading of 1.1 V is 204 at 5.5 V (+10 %).
* Raw reading of 1.1 V is 1126000 / VCC_MILLIVOLT
* @return true if 5 % overvoltage reached
*/
bool isVCCOvervoltage() {
Expand All @@ -660,6 +727,21 @@ bool isVCCOvervoltageSimple() {
return (sVCCVoltageMillivolt > VCC_OVERVOLTAGE_THRESHOLD_MILLIVOLT);
}

// Version not using readVCCVoltageMillivoltSimple()
bool isVCCTooHighSimple() {
ADMUX = ADC_1_1_VOLT_CHANNEL_MUX | (DEFAULT << SHIFT_VALUE_FOR_REFERENCE);
// ADCSRB = 0; // Only active if ADATE is set to 1.
// ADSC-StartConversion ADIF-Reset Interrupt Flag - NOT free running mode
ADCSRA = (_BV(ADEN) | _BV(ADSC) | _BV(ADIF) | ADC_PRESCALE128); // 128 -> 104 microseconds per ADC conversion at 16 MHz --- Arduino default
// wait for single conversion to finish
loop_until_bit_is_clear(ADCSRA, ADSC);

// Get value
uint16_t tRawValue = ADCL | (ADCH << 8);

return tRawValue < 1126000 / VCC_OVERVOLTAGE_THRESHOLD_MILLIVOLT;
}

/*
* Temperature sensor is enabled by selecting the appropriate channel.
* Different formula for 328P and 328PB!
Expand All @@ -671,18 +753,21 @@ float getCPUTemperatureSimple(void) {
return 0.0;
#else
// use internal 1.1 volt as reference. 4 times oversample. Assume the signal has noise, but never verified :-(
uint16_t tTempRaw = readADCChannelWithReferenceOversample(ADC_TEMPERATURE_CHANNEL_MUX, INTERNAL, 2);
uint16_t tTemperatureRaw = readADCChannelWithReferenceOversample(ADC_TEMPERATURE_CHANNEL_MUX, INTERNAL, 2);
#if defined(LOCAL_DEBUG)
Serial.print(F("TempRaw="));
Serial.println(tTempRaw);
Serial.println(tTemperatureRaw);
#endif

#if defined(__AVR_ATmega328PB__)
tTempRaw -= 245;
return (float)tTempRaw;
tTemperatureRaw -= 245;
return (float)tTemperatureRaw;
#elif defined(__AVR_ATtiny85__)
tTemperatureRaw -= 273; // 273 and 1.1666 are values from the datasheet
return (float)tTemperatureRaw / 1.1666;
#else
tTempRaw -= 317;
return (float) tTempRaw / 1.22;
tTemperatureRaw -= 317;
return (float) tTemperatureRaw / 1.22;
#endif
#endif
}
Expand All @@ -704,7 +789,7 @@ float getCPUTemperature(void) {
}

#else // defined(ADC_UTILS_ARE_AVAILABLE)
// Dummy definition of functions defined in ADCUtils to compile examples without errors
// Dummy definition of functions defined in ADCUtils to compile examples for non AVR platforms without errors
/*
* Persistent storage for VCC value
*/
Expand Down
9 changes: 9 additions & 0 deletions examples/BasicDistance/HCSR04.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,15 @@
//#define USE_PIN_CHANGE_INTERRUPT_D0_TO_D7 // using PCINT2_vect - PORT D
//#define USE_PIN_CHANGE_INTERRUPT_D8_TO_D13 // using PCINT0_vect - PORT B - Pin 13 is feedback output
//#define USE_PIN_CHANGE_INTERRUPT_A0_TO_A5 // using PCINT1_vect - PORT C
#if __has_include("digitalWriteFast.h")
#include "digitalWriteFast.h"
#else
#define pinModeFast pinMode
#define digitalReadFast digitalRead
#define digitalWriteFast digitalWrite
#define digitalToggleFast(P) digitalWrite(P, ! digitalRead(P))
#endif

#include "HCSR04.h"

//#define DEBUG
Expand Down Expand Up @@ -132,6 +140,7 @@ void initUSDistancePin(uint8_t aTriggerOutEchoInPin) {
#if !defined (TRIGGER_OUT_PIN)
sTriggerOutPin = aTriggerOutEchoInPin;
#endif
(void) aTriggerOutEchoInPin;
sHCSR04Mode = HCSR04_MODE_USE_1_PIN;
}

Expand Down
15 changes: 1 addition & 14 deletions examples/BasicDistance/RobotCarPinDefinitionsAndMore.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,20 +235,7 @@
# if !defined(LED_BUILTIN) && !defined(CAR_IS_ESP32_CAM_BASED)
#define LED_BUILTIN PB1
# endif
#define TONE_LEDC_CHANNEL 1 // Using channel 1 makes tone() independent of receiving timer -> No need to stop receiving timer.
void tone(uint8_t _pin, unsigned int frequency){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
}
void tone(uint8_t _pin, unsigned int frequency, unsigned long duration){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
delay(duration);
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}
void noTone(uint8_t _pin){
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}

#else // NANO_BASED
// Uno based
// Pin A0 for VCC monitoring - ADC channel 2
Expand Down
15 changes: 1 addition & 14 deletions examples/BasicIRControl/RobotCarPinDefinitionsAndMore.h
Original file line number Diff line number Diff line change
Expand Up @@ -235,20 +235,7 @@
# if !defined(LED_BUILTIN) && !defined(CAR_IS_ESP32_CAM_BASED)
#define LED_BUILTIN PB1
# endif
#define TONE_LEDC_CHANNEL 1 // Using channel 1 makes tone() independent of receiving timer -> No need to stop receiving timer.
void tone(uint8_t _pin, unsigned int frequency){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
}
void tone(uint8_t _pin, unsigned int frequency, unsigned long duration){
ledcAttachPin(_pin, TONE_LEDC_CHANNEL);
ledcWriteTone(TONE_LEDC_CHANNEL, frequency);
delay(duration);
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}
void noTone(uint8_t _pin){
ledcWriteTone(TONE_LEDC_CHANNEL, 0);
}

#else // NANO_BASED
// Uno based
// Pin A0 for VCC monitoring - ADC channel 2
Expand Down
Loading

0 comments on commit 2c23c53

Please sign in to comment.