Skip to content

Commit

Permalink
getSpeed refactor (#17)
Browse files Browse the repository at this point in the history
* getSpeed refactor

getSpeed now returns the _pwmVal setted with setSpeed if the motor is moving.
Otherwise return 0.

* typo in examples
  • Loading branch information
AndreaLombardo authored Jan 13, 2023
1 parent b1631d6 commit e8f024f
Show file tree
Hide file tree
Showing 4 changed files with 59 additions and 123 deletions.
21 changes: 8 additions & 13 deletions examples/L298N-Fade/L298N-Fade.ino
Original file line number Diff line number Diff line change
Expand Up @@ -28,21 +28,18 @@ L298N motor(EN, IN1, IN2);
int speedness = 0;
int speedAmount = 1;

void setup()
{
void setup() {
// Used to display information
Serial.begin(9600);

// Wait for Serial Monitor to be opened
while (!Serial)
{
//do nothing
while (!Serial) {
// do nothing
}
}

void loop()
{
// Apply faded speed to both motors
void loop() {
// Apply faded speed
motor.setSpeed(speedness);

// Tell motor A to go forward (may depend by your wiring)
Expand All @@ -51,15 +48,14 @@ void loop()
// Alternative method:
// motor.run(L298N::FORWARD);

//print the motor status in the serial monitor
// print the motor status in the serial monitor
printSomeInfo();

// Change the "speedness" for next time through the loop:
speedness = speedness + speedAmount;

// Reverse the direction of the fading at the ends of the fade:
if (speedness <= 0 || speedness >= 255)
{
if (speedness <= 0 || speedness >= 255) {
speedAmount = -speedAmount;
}

Expand All @@ -70,8 +66,7 @@ void loop()
/*
Print some informations in Serial Monitor
*/
void printSomeInfo()
{
void printSomeInfo() {
Serial.print("Motor is moving = ");
Serial.print(motor.isMoving() ? "YES" : "NO");
Serial.print(" at speed = ");
Expand Down
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
name=L298N
version=2.0.2
version=2.0.3
author=Andrea Lombardo
maintainer=Andrea Lombardo
sentence=L298N library for Arduino
Expand Down
119 changes: 48 additions & 71 deletions src/L298N.cpp
Original file line number Diff line number Diff line change
@@ -1,15 +1,13 @@
/*
L298N.cpp - Libreria per gestire i movimenti di un motore DC con il modulo L298N
Autore: Andrea Lombardo
Sito web: http://www.lombardoandrea.com
L298N.cpp - Libreria per gestire i movimenti di un motore DC con il modulo
L298N Autore: Andrea Lombardo Sito web: http://www.lombardoandrea.com
*/

#include "L298N.h"

typedef void (*CallBackFunction)();

L298N::L298N(uint8_t pinEnable, uint8_t pinIN1, uint8_t pinIN2)
{
L298N::L298N(uint8_t pinEnable, uint8_t pinIN1, uint8_t pinIN2) {
_pinEnable = pinEnable;
_pinIN1 = pinIN1;
_pinIN2 = pinIN2;
Expand All @@ -24,12 +22,11 @@ L298N::L298N(uint8_t pinEnable, uint8_t pinIN1, uint8_t pinIN2)
pinMode(_pinIN2, OUTPUT);
}

L298N::L298N(uint8_t pinIN1, uint8_t pinIN2)
{
L298N::L298N(uint8_t pinIN1, uint8_t pinIN2) {
_pinEnable = -1;
_pinIN1 = pinIN1;
_pinIN2 = pinIN2;
_pwmVal = 255; // It's always at the max speed due to jumper on module
_pwmVal = 255; // It's always at the max speed due to jumper on module
_isMoving = false;
_canMove = true;
_lastMs = 0;
Expand All @@ -39,18 +36,15 @@ L298N::L298N(uint8_t pinIN1, uint8_t pinIN2)
pinMode(_pinIN2, OUTPUT);
}

void L298N::setSpeed(unsigned short pwmVal)
{
void L298N::setSpeed(unsigned short pwmVal) {
_pwmVal = pwmVal;
}

unsigned short L298N::getSpeed()
{
return _pwmVal;
unsigned short L298N::getSpeed() {
return this->isMoving() ? _pwmVal : 0;
}

void L298N::forward()
{
void L298N::forward() {
digitalWrite(_pinIN1, HIGH);
digitalWrite(_pinIN2, LOW);

Expand All @@ -60,8 +54,7 @@ void L298N::forward()
_isMoving = true;
}

void L298N::backward()
{
void L298N::backward() {
digitalWrite(_pinIN1, LOW);
digitalWrite(_pinIN2, HIGH);

Expand All @@ -71,48 +64,43 @@ void L298N::backward()
_isMoving = true;
}

void L298N::run(L298N::Direction direction)
{
switch (direction)
{
case BACKWARD:
this->backward();
break;
case FORWARD:
this->forward();
break;
case STOP:
this->stop();
break;
}
}

//Timing and callback

void L298N::runFor(unsigned long delay, L298N::Direction direction, CallBackFunction callback)
{

if ((_lastMs == 0) && _canMove)
{
_lastMs = millis();

switch (direction)
{
case FORWARD:
this->forward();
break;
void L298N::run(L298N::Direction direction) {
switch (direction) {
case BACKWARD:
this->backward();
break;
case FORWARD:
this->forward();
break;
case STOP:
default:
this->stop();
break;
}
}

// Timing and callback

void L298N::runFor(unsigned long delay,
L298N::Direction direction,
CallBackFunction callback) {
if ((_lastMs == 0) && _canMove) {
_lastMs = millis();

switch (direction) {
case FORWARD:
this->forward();
break;
case BACKWARD:
this->backward();
break;
case STOP:
default:
this->stop();
break;
}
}

if (((millis() - _lastMs) > delay) && _canMove)
{
if (((millis() - _lastMs) > delay) && _canMove) {
this->stop();
_lastMs = 0;
_canMove = false;
Expand All @@ -121,33 +109,27 @@ void L298N::runFor(unsigned long delay, L298N::Direction direction, CallBackFunc
}
}

void L298N::runFor(unsigned long delay, L298N::Direction direction)
{
void L298N::runFor(unsigned long delay, L298N::Direction direction) {
this->runFor(delay, direction, fakeCallback);
}

void L298N::forwardFor(unsigned long delay, CallBackFunction callback)
{
void L298N::forwardFor(unsigned long delay, CallBackFunction callback) {
this->runFor(delay, FORWARD, callback);
}

void L298N::forwardFor(unsigned long delay)
{
void L298N::forwardFor(unsigned long delay) {
this->runFor(delay, FORWARD);
}

void L298N::backwardFor(unsigned long delay, CallBackFunction callback)
{
void L298N::backwardFor(unsigned long delay, CallBackFunction callback) {
this->runFor(delay, BACKWARD, callback);
}

void L298N::backwardFor(unsigned long delay)
{
void L298N::backwardFor(unsigned long delay) {
this->runFor(delay, BACKWARD);
}

void L298N::stop()
{
void L298N::stop() {
digitalWrite(_pinIN1, LOW);
digitalWrite(_pinIN2, LOW);

Expand All @@ -157,21 +139,16 @@ void L298N::stop()
_isMoving = false;
}

void L298N::reset()
{
void L298N::reset() {
_canMove = true;
}

boolean L298N::isMoving()
{
boolean L298N::isMoving() {
return _isMoving;
}

L298N::Direction L298N::getDirection()
{
L298N::Direction L298N::getDirection() {
return _direction;
}

void L298N::fakeCallback()
{
}
void L298N::fakeCallback() {}
40 changes: 2 additions & 38 deletions src/L298NX2.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ void L298NX2::setSpeedA(unsigned short pwmVal)

unsigned short L298NX2::getSpeedA()
{
return _motorA.getSpeed();
return _motorA.isMoving() ? _motorA.getSpeed() : 0;
}

void L298NX2::forwardA()
Expand Down Expand Up @@ -126,24 +126,6 @@ L298N::Direction L298NX2::getDirectionA()
return _motorA.getDirection();
}

/*
*/

//Motor B
void L298NX2::setSpeedB(unsigned short pwmVal)
{
Expand All @@ -152,7 +134,7 @@ void L298NX2::setSpeedB(unsigned short pwmVal)

unsigned short L298NX2::getSpeedB()
{
return _motorB.getSpeed();
return _motorB.isMoving() ? _motorB.getSpeed() : 0;
}

void L298NX2::forwardB()
Expand Down Expand Up @@ -218,24 +200,6 @@ L298N::Direction L298NX2::getDirectionB()
return _motorB.getDirection();
}

/*
*/
// Both
void L298NX2::setSpeed(unsigned short pwmVal)
{
Expand Down

0 comments on commit e8f024f

Please sign in to comment.