Skip to content

Commit

Permalink
Update test code
Browse files Browse the repository at this point in the history
  • Loading branch information
Chi-EEE committed Jan 1, 2024
1 parent 01154bd commit 127d8e8
Show file tree
Hide file tree
Showing 3 changed files with 112 additions and 68 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -6,45 +6,42 @@
#include "pigpio.h"
#include "pigpiod_if2.h"

namespace tb6612
enum MotorStatus
{
enum MotorStatus
{
UNINITIALIZED,
FORWARD,
BACKWARD
};
class Motor
{
public:
Motor(
const int &direction_channel,
const int &pwn = 0,
const bool &offset = true,
const int &frequency = 1000);

void setSpeed(int speed);
void forward();
void backward();
void stop();

MotorStatus getStatus() const { return this->status; }
int getSpeed() const { return this->speed; }
bool isMoving() const { return this->speed > 0; }

private:
const int direction_channel;
const int pwm;
const bool offset;

const bool forward_offset;
const bool backward_offset;

const int frequency;

MotorStatus status = UNINITIALIZED;
int speed = 0;
}
UNINITIALIZED,
FORWARD,
BACKWARD
};
class Motor
{
public:
Motor(
const int &direction_channel,
const int &pwn = 0,
const bool &offset = true,
const int &frequency = 1000);

void setSpeed(int speed);
void forward();
void backward();
void stop();

MotorStatus getStatus() const { return this->status; }
int getSpeed() const { return this->speed; }
bool isMoving() const { return this->speed > 0; }

private:
const int direction_channel;
const int pwm;
const bool offset;

const bool forward_offset;
const bool backward_offset;

const int frequency;

MotorStatus status = UNINITIALIZED;
int speed = 0;
}

#endif
57 changes: 27 additions & 30 deletions app/raspberry_pi/repository/packages/t/tb6612/tb6612/src/TB6612.cpp
Original file line number Diff line number Diff line change
@@ -1,38 +1,35 @@
#include "TB6612.h"

namespace tb6612
Motor::Motor(const int &direction_channel, const int &pwn, const bool &offset, const int &frequency)
: direction_channel(direction_channel),
pwm(pwm),
offset(offset),
forward_offset(offset),
backward_offset(!offset),
frequency(frequency)
{
Motor::Motor(const int &direction_channel, const int &pwn, const bool &offset, const int &frequency)
: direction_channel(direction_channel),
pwm(pwm),
offset(offset),
forward_offset(offset),
backward_offset(!offset),
frequency(frequency)
{
gpioSetMode(direction_channel, PI_OUTPUT);
}
gpioSetMode(direction_channel, PI_OUTPUT);
}

Motor::setSpeed(int speed)
{
this->speed = speed;
gpioHardwarePWM(pwm, 1000, speed);
}
Motor::setSpeed(int speed)
{
this->speed = speed;
gpioHardwarePWM(pwm, 1000, speed);
}

void Motor::forward()
{
gpioWrite(direction_channel, forward_offset);
this->status = FORWARD;
}
void Motor::forward()
{
gpioWrite(direction_channel, forward_offset);
this->status = FORWARD;
}

void Motor::backward()
{
gpioWrite(direction_channel, backward_offset);
this->status = BACKWARD;
}
void Motor::backward()
{
gpioWrite(direction_channel, backward_offset);
this->status = BACKWARD;
}

void Motor::stop()
{
this->setSpeed(0);
}
void Motor::stop()
{
this->setSpeed(0);
}
50 changes: 50 additions & 0 deletions app/raspberry_pi/tests/tb6612/test_rear_wheels.cpp
Original file line number Diff line number Diff line change
@@ -1,10 +1,60 @@
#include <thread>

#include "TB6612.h"

#include "pigpio.h"
#include "pigpiod_if2.h"

void setupGPIOMotor();

using namespace tb6612;

class BackWheels {
private:
static constexpr int motor_A = 17;
static constexpr int motor_B = 27;

static constexpr int pwm_A = 4;
static constexpr int pwm_B = 5;
public:
BackWheels(const int &bus_number = 1) : pwm(bus_number) {

}

void forward() {
this->motor_A.forward();
this->motor_B.forward();
}

void backward() {
this->motor_A.backward();
this->motor_B.backward();
}

void stop() {
this->motor_A.stop();
this->motor_B.stop();
}

void setSpeed(int speed) {
this->motor_A.setSpeed(speed);
this->motor_B.setSpeed(speed);
this->speed = speed;
}

private:
bool forward_A = true;
bool forward_B = true;

TB6612 motor_A = TB6612(motor_A, pwm_A, forward_A);
TB6612 motor_B = TB6612(motor_B, pwm_B, forward_B);

PCA9685 pwm;

int speed = 0;
}


int main()
{
setupGPIOMotor();
Expand Down

0 comments on commit 127d8e8

Please sign in to comment.