Skip to content

Commit

Permalink
Bumped version to 2.2.0. Added 2 functions startGoDistanceMillimeterW…
Browse files Browse the repository at this point in the history
…ithSpeed(uint8_t aRequestedSpeedPWM, ...)
  • Loading branch information
ArminJo committed Oct 25, 2024
1 parent 8506dd9 commit 740cc86
Show file tree
Hide file tree
Showing 22 changed files with 270 additions and 128 deletions.
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,9 @@ VIN sensing
<br/>

# Revision History
### Version 2.1.1
### Version 2.2.0
- Added 2 functions startGoDistanceMillimeterWithSpeed(uint8_t aRequestedSpeedPWM, ...).
- ESP32 core 3.x support.
- Improved examples, especially follower examples.

### Version 2.1.0
Expand Down
2 changes: 1 addition & 1 deletion examples/Basic/RobotCarConfigurations.h
Original file line number Diff line number Diff line change
Expand Up @@ -317,7 +317,7 @@
* BASIC CONFIGURATION for ESP32-Cam car
* Car controlled by an ESP32-Cam module
*/
#if defined(ESP32) // a temporarily hack
#if defined(ESP32) && !defined(CAR_IS_ESP32_CAM_BASED) // a temporarily hack
#define CAR_IS_ESP32_CAM_BASED
#endif
#if defined(CAR_IS_ESP32_CAM_BASED)
Expand Down
19 changes: 10 additions & 9 deletions examples/IRDispatcherControl/Distance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,16 @@
#include "HCSR04.hpp" // include sources
#include "RobotCarConfigurations.h" // helps the pretty printer / Ctrl F

#if defined(CAR_HAS_SERVO) && defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#define DISABLE_SERVO_TIMER_AUTO_INITIALIZE // saves 70 bytes program space
#if defined(CAR_HAS_DISTANCE_SERVO)
# if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#include "LightweightServo.hpp"
#endif
# if defined(_LIGHTWEIGHT_SERVO_HPP)
LightweightServo DistanceServo; // The pan servo instance for distance sensor
# else // LightweightServo is not applicable for this CPU
#undef USE_LIGHTWEIGHT_SERVO_LIBRARY
# endif
# endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)

#if defined(CAR_HAS_DISTANCE_SERVO)
# if !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
Servo DistanceServo; // The pan servo instance for distance sensor
# endif
Expand Down Expand Up @@ -87,7 +91,7 @@ ForwardDistancesInfoStruct sForwardDistancesInfo;
void initDistance() {
getDistanceModesFromPins();

#if defined(CAR_HAS_DISTANCE_SERVO) && !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#if defined(CAR_HAS_DISTANCE_SERVO)
DistanceServo.attach(DISTANCE_SERVO_PIN);
#endif

Expand Down Expand Up @@ -492,11 +496,8 @@ void DistanceServoWriteAndWaitForStop(uint8_t aTargetDegrees, bool doWaitForStop
// The servo is top down and therefore inverted
aTargetDegrees = 180 - aTargetDegrees;
#endif
#if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
write10(aTargetDegrees);
#else
DistanceServo.write(aTargetDegrees);
#endif


/*
* Delay until stopped
Expand Down
8 changes: 4 additions & 4 deletions examples/IRDispatcherControl/RobotCarIRCommands.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -80,19 +80,19 @@ void doReset() {
void goForward() {
if (IRDispatcher.IRReceivedData.isRepeat) {
// if repeat was pressed, we enable a "fast" stop
RobotCar.startGoDistanceMillimeter(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER / 4,
RobotCar.startGoDistanceMillimeterWithSpeed(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER / 4,
DIRECTION_FORWARD);
} else {
RobotCar.startGoDistanceMillimeter(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER,
RobotCar.startGoDistanceMillimeterWithSpeed(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER,
DIRECTION_FORWARD);
}
}
void goBackward() {
if (IRDispatcher.IRReceivedData.isRepeat) {
RobotCar.startGoDistanceMillimeter(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER / 4,
RobotCar.startGoDistanceMillimeterWithSpeed(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER / 4,
DIRECTION_BACKWARD);
} else {
RobotCar.startGoDistanceMillimeter(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER,
RobotCar.startGoDistanceMillimeterWithSpeed(RobotCar.rightCarMotor.DriveSpeedPWM, DEFAULT_CIRCUMFERENCE_MILLIMETER,
DIRECTION_BACKWARD);
}
}
Expand Down
19 changes: 10 additions & 9 deletions examples/RobotCarBasic/Distance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,16 @@
#include "HCSR04.hpp" // include sources
#include "RobotCarConfigurations.h" // helps the pretty printer / Ctrl F

#if defined(CAR_HAS_SERVO) && defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#define DISABLE_SERVO_TIMER_AUTO_INITIALIZE // saves 70 bytes program space
#if defined(CAR_HAS_DISTANCE_SERVO)
# if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#include "LightweightServo.hpp"
#endif
# if defined(_LIGHTWEIGHT_SERVO_HPP)
LightweightServo DistanceServo; // The pan servo instance for distance sensor
# else // LightweightServo is not applicable for this CPU
#undef USE_LIGHTWEIGHT_SERVO_LIBRARY
# endif
# endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)

#if defined(CAR_HAS_DISTANCE_SERVO)
# if !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
Servo DistanceServo; // The pan servo instance for distance sensor
# endif
Expand Down Expand Up @@ -87,7 +91,7 @@ ForwardDistancesInfoStruct sForwardDistancesInfo;
void initDistance() {
getDistanceModesFromPins();

#if defined(CAR_HAS_DISTANCE_SERVO) && !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#if defined(CAR_HAS_DISTANCE_SERVO)
DistanceServo.attach(DISTANCE_SERVO_PIN);
#endif

Expand Down Expand Up @@ -492,11 +496,8 @@ void DistanceServoWriteAndWaitForStop(uint8_t aTargetDegrees, bool doWaitForStop
// The servo is top down and therefore inverted
aTargetDegrees = 180 - aTargetDegrees;
#endif
#if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
write10(aTargetDegrees);
#else
DistanceServo.write(aTargetDegrees);
#endif


/*
* Delay until stopped
Expand Down
19 changes: 10 additions & 9 deletions examples/RobotCarBlueDisplay/Distance.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,12 +33,16 @@
#include "HCSR04.hpp" // include sources
#include "RobotCarConfigurations.h" // helps the pretty printer / Ctrl F

#if defined(CAR_HAS_SERVO) && defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#define DISABLE_SERVO_TIMER_AUTO_INITIALIZE // saves 70 bytes program space
#if defined(CAR_HAS_DISTANCE_SERVO)
# if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#include "LightweightServo.hpp"
#endif
# if defined(_LIGHTWEIGHT_SERVO_HPP)
LightweightServo DistanceServo; // The pan servo instance for distance sensor
# else // LightweightServo is not applicable for this CPU
#undef USE_LIGHTWEIGHT_SERVO_LIBRARY
# endif
# endif // defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)

#if defined(CAR_HAS_DISTANCE_SERVO)
# if !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
Servo DistanceServo; // The pan servo instance for distance sensor
# endif
Expand Down Expand Up @@ -87,7 +91,7 @@ ForwardDistancesInfoStruct sForwardDistancesInfo;
void initDistance() {
getDistanceModesFromPins();

#if defined(CAR_HAS_DISTANCE_SERVO) && !defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
#if defined(CAR_HAS_DISTANCE_SERVO)
DistanceServo.attach(DISTANCE_SERVO_PIN);
#endif

Expand Down Expand Up @@ -492,11 +496,8 @@ void DistanceServoWriteAndWaitForStop(uint8_t aTargetDegrees, bool doWaitForStop
// The servo is top down and therefore inverted
aTargetDegrees = 180 - aTargetDegrees;
#endif
#if defined(USE_LIGHTWEIGHT_SERVO_LIBRARY)
write10(aTargetDegrees);
#else
DistanceServo.write(aTargetDegrees);
#endif


/*
* Delay until stopped
Expand Down
29 changes: 23 additions & 6 deletions examples/RobotCarBlueDisplay/LightweightServo.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,20 +41,21 @@
#define ISR_COUNT_FOR_2_5_MILLIS (F_CPU / (8 * 400)) // 5000 For 400 Hz, 2.5 ms using a prescaler of 8.

#if defined(__AVR_ATmega2560__)
#define LEIGHTWEIGHT_SERVO_CHANNEL_A_PIN 46
#define LEIGHTWEIGHT_SERVO_CHANNEL_B_PIN 45
#define LEIGHTWEIGHT_SERVO_CHANNEL_C_PIN 44
#define LIGHTWEIGHT_SERVO_CHANNEL_A_PIN 46
#define LIGHTWEIGHT_SERVO_CHANNEL_B_PIN 45
#define LIGHTWEIGHT_SERVO_CHANNEL_C_PIN 44
#elif defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328__) || defined (__AVR_ATmega328PB__)
#define LEIGHTWEIGHT_SERVO_CHANNEL_A_PIN 9
#define LEIGHTWEIGHT_SERVO_CHANNEL_B_PIN 10
#define LIGHTWEIGHT_SERVO_CHANNEL_A_PIN 9
#define LIGHTWEIGHT_SERVO_CHANNEL_B_PIN 10
#endif

void initLightweightServoPins(); // currently only pin 44 = OC5C/PL5, 45 = OC5B/PL4 + 46 = OC5A/PL3 on 2560 and pin 9 = OC1A + 10 = OC1B on 328
void checkAndInitLightweightServoPin(uint8_t aPin);
void deinitLightweightServoPin(uint8_t aPin); // Set pin to input and disable non-inverting Compare Output mode

int writeLightweightServoPin(int aDegree, uint8_t aPin, bool aUpdateFast = false);
void writeMicrosecondsLightweightServoPin(int aMicroseconds, uint8_t aPin, bool aUpdateFast = false);
// The last parameter requires 8 byte more than DISABLE_SERVO_TIMER_AUTO_INITIALIZE, if false, but saves around 60 bytes anyway
void writeMicrosecondsLightweightServoPin(int aMicroseconds, uint8_t aPin, bool aUpdateFast = false, bool aDoAutoInit = true);

void setLightweightServoPulseMicrosFor0And180Degree(int aMicrosecondsForServo0Degree, int a180DegreeValue);
void setLightweightServoRefreshRate(unsigned int aRefreshPeriodMicroseconds);
Expand Down Expand Up @@ -89,6 +90,22 @@ int writeLightweightServo(int aDegree, bool aUsePin9, bool aUpdateFast = false);
void writeMicrosecondsLightweightServo(int aMicroseconds, bool aUsePin9, bool aUpdateFast = false);
#endif // Old and fast ATmega328 functions

class LightweightServo {
public:
uint8_t attach(int aPin);
uint8_t attach(int aPin, int aMicrosecondsForServo0Degree, int aMicrosecondsForServo180Degree);
void detach();
void write(int aTargetDegreeOrMicrosecond);
void writeMicroseconds(int aTargetMicrosecond); // Write pulse width in microseconds
/*
* Variables to enable adjustment for different servo types
* 544 and 2400 are values compatible with standard arduino values
*/
int MicrosecondsForServo0Degree = 544;
int MicrosecondsForServo180Degree = 2400;
uint8_t LightweightServoPin;
};

#endif // defined(__AVR_ATmega328P__) || defined(__AVR_ATmega328__) || defined (__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__)

/*
Expand Down
Loading

0 comments on commit 740cc86

Please sign in to comment.