Skip to content

Commit

Permalink
Merge branch 'tb6612'
Browse files Browse the repository at this point in the history
  • Loading branch information
SimonPucheu committed Mar 15, 2023
2 parents a2f9f26 + 043419f commit 944cbed
Show file tree
Hide file tree
Showing 4 changed files with 42 additions and 98 deletions.
54 changes: 36 additions & 18 deletions src/Motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5,41 +5,59 @@
/**
* Setup the Motor
*/
Motor::Motor(uint8_t in1, uint8_t in2, uint8_t pwm, uint8_t offset, uint8_t standBy, int iFromMin = 0, int iFromMax = 255, int iToMin = 0, int iToMax = 255)
Motor::Motor(uint8_t iIn1, uint8_t iIn2, uint8_t iPwm, uint8_t iStandBy, int iFromMin = 0, int iFromMax = 255, int iToMin = 0, int iToMax = 255)
{
motor = TB6612(in1, in2, pwm, offset, standBy);
fromMin = iFromMin;
fromMax = iFromMax;
toMin = iToMin;
toMax = iToMax;
fromMin = iFromMin;
fromMax = iFromMax;
toMin = iToMin;
toMax = iToMax;
in1 = iIn1;
in2 = iIn2;
pwm = iPwm;
standby = iStandBy;
pinMode(in1, OUTPUT);
pinMode(in2, OUTPUT);
pinMode(pwm, OUTPUT);
pinMode(standby, OUTPUT);
digitalWrite(standby, HIGH);
}

void Motor::move(int speed)
{
motor.drive((map(speed, fromMin, fromMax, toMin, toMax)));
if (speed > 0)
{
forward(speed);
}
if (speed < 0)
{
backward(-speed);
}
}

void Motor::forward(int speed)
{
motor.drive((map(speed, fromMin, fromMax, toMin, toMax)));
}

void Motor::forward(int speed, int duration)
{
motor.drive((map(speed, fromMin, fromMax, toMin, toMax)), duration);
digitalWrite(in1, HIGH);
digitalWrite(in2, LOW);
analogWrite(pwm, map(speed, fromMin, fromMax, toMin, toMax));
}

void Motor::backward(int speed)
{
motor.drive(-(map(speed, fromMin, fromMax, toMin, toMax)));
digitalWrite(in1, LOW);
digitalWrite(in2, HIGH);
analogWrite(pwm, map(speed, fromMin, fromMax, toMin, toMax));
}

void Motor::backward(int speed, int duration)
void Motor::stop()
{
motor.drive(-(map(speed, fromMin, fromMax, toMin, toMax)), duration);
digitalWrite(in1, LOW);
digitalWrite(in2, LOW);
analogWrite(pwm, 0);
}

void Motor::stop()
void Motor::brake()
{
motor.brake();
digitalWrite(in1, HIGH);
digitalWrite(in2, HIGH);
analogWrite(pwm, 0);
}
12 changes: 6 additions & 6 deletions src/Motor.h
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
#include <Arduino.h>

#include "TB6612.h"

class Motor
{
public:
Motor(uint8_t in1, uint8_t in2, uint8_t pwm, uint8_t offset, uint8_t standBy, int iFromMin = 0, int iFromMax = 255, int iToMin = 0, int iToMax = 255);
Motor(uint8_t iIn1, uint8_t iIn2, uint8_t iPwm, uint8_t iStandBy, int iFromMin = 0, int iFromMax = 255, int iToMin = 0, int iToMax = 255);
void move(int speed);
void forward(int speed);
void forward(int speed, int duration);
void backward(int speed);
void backward(int speed, int duration);
void stop();
void brake();
int in1;
int in2;
int pwm;
int standby;
int fromMin = 0;
int fromMax = 255;
int toMin = 0;
int toMax = 255;
TB6612 motor = TB6612(0, 0, 0, 0, 0);
};
57 changes: 0 additions & 57 deletions src/TB6612.cpp

This file was deleted.

17 changes: 0 additions & 17 deletions src/TB6612.h

This file was deleted.

0 comments on commit 944cbed

Please sign in to comment.