Skip to content

Commit

Permalink
Cleaned up comments & updated variable
Browse files Browse the repository at this point in the history
Cleaned up some of the comments, adjusted formatting to add whitespace.

Changed Motor class member en_a to enc_a and en_b to enc_b to avoid confusion with L293D Enable pins.
  • Loading branch information
DingoOz committed Nov 20, 2021
1 parent a027ab3 commit 5b7e23d
Show file tree
Hide file tree
Showing 5 changed files with 145 additions and 49 deletions.
24 changes: 0 additions & 24 deletions Motor.h

This file was deleted.

88 changes: 88 additions & 0 deletions motor_test/motor_test.ino
Original file line number Diff line number Diff line change
@@ -0,0 +1,88 @@
// Motor A connections
int enA = 9;
int in1 = 9;
int in2 = 8;
// Motor B connections
int enB = 3;
int in3 = 10;
int in4 = 11;

void setup() {
// Set all the motor control pins to outputs
pinMode(enA, OUTPUT);
pinMode(enB, OUTPUT);
pinMode(in1, OUTPUT);
pinMode(in2, OUTPUT);
pinMode(in3, OUTPUT);
pinMode(in4, OUTPUT);

// Turn off motors - Initial state
digitalWrite(in1, LOW);
digitalWrite(in2, LOW);
digitalWrite(in3, LOW);
digitalWrite(in4, LOW);
}

void loop() {
directionControl();
delay(1000);
speedControl();
delay(1000);
}

// This function lets you control spinning direction of motors
void directionControl() {
// Set motors to maximum speed
// For PWM maximum possible values are 0 to 255
analogWrite(enA, 255);
analogWrite(enB, 255);

// Turn on motor A & B
digitalWrite(in1, HIGH);
digitalWrite(in2, LOW);
digitalWrite(in3, HIGH);
digitalWrite(in4, LOW);
delay(2000);

// Now change motor directions
digitalWrite(in1, LOW);
digitalWrite(in2, HIGH);
digitalWrite(in3, LOW);
digitalWrite(in4, HIGH);
delay(2000);

// Turn off motors
digitalWrite(in1, LOW);
digitalWrite(in2, LOW);
digitalWrite(in3, LOW);
digitalWrite(in4, LOW);
}

// This function lets you control speed of the motors
void speedControl() {
// Turn on motors
digitalWrite(in1, LOW);
digitalWrite(in2, HIGH);
digitalWrite(in3, LOW);
digitalWrite(in4, HIGH);

// Accelerate from zero to maximum speed
for (int i = 0; i < 256; i++) {
analogWrite(enA, i);
analogWrite(enB, i);
delay(20);
}

// Decelerate from maximum speed to zero
for (int i = 255; i >= 0; --i) {
analogWrite(enA, i);
analogWrite(enB, i);
delay(20);
}

// Now turn off motors
digitalWrite(in1, LOW);
digitalWrite(in2, LOW);
digitalWrite(in3, LOW);
digitalWrite(in4, LOW);
}
10 changes: 5 additions & 5 deletions Motor.cpp → navbot/Motor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,15 +2,15 @@
#include "Motor.h"


Motor::Motor(int plus, int minus, int en_a, int en_b) {
Motor::Motor(int plus, int minus, int enc_a, int enc_b) {
pinMode(plus,OUTPUT);
pinMode(minus,OUTPUT);
pinMode(en_a,INPUT_PULLUP);
pinMode(en_b,INPUT_PULLUP);
pinMode(enc_a,INPUT_PULLUP);
pinMode(enc_b,INPUT_PULLUP);
Motor::plus = plus;
Motor::minus = minus;
Motor::en_a = en_a;
Motor::en_b = en_b;
Motor::enc_a = enc_a;
Motor::enc_b = enc_b;
}

void Motor::rotate(int value) {
Expand Down
31 changes: 31 additions & 0 deletions navbot/Motor.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,31 @@
/*
Motor.h - Library for working with the Cytron SPG30E-30K or other DC motor with quadrant encoder.
Created by Vinay Lanka, January 27, 2021.
Update - Dingo 21 November 2021
+ en_a and en_b updated to enc_a and enc_b to avoid confusion with "Enable A and Enable B on the L293D motor driver (which is not used)
+ comments update with details
*/
#ifndef Motor_h
#define Motor_h

#include "Arduino.h"

class Motor {
public:
//Constructor for Motor - 'Plus' and 'Minus' are the Motor pins to connect the output to / enc_a and enc_b are the encoder inputs
Motor(int plus, int minus, int enc_a, int enc_b);

//Rotate motor shaft based on a percentage value
void rotate(int value);

//Motor Outputs - plus is one direction and minus is the other
int plus;
int minus;

//Encoder Inputs
int enc_a;
int enc_b;
};

#endif
41 changes: 21 additions & 20 deletions navbot/navbot.ino
Original file line number Diff line number Diff line change
@@ -1,10 +1,11 @@
//AGV Machine - Vinay Lanka
//Updates by Dingo

//Import Motor - Cytron SPG30E-30K
#include "Motor.h"
#include <ros.h>
#include <geometry_msgs/Twist.h>
#include<PID_v1.h>
#include <PID_v1.h>
#include <geometry_msgs/Vector3Stamped.h>
#include <ros/time.h>

Expand All @@ -13,8 +14,8 @@ ros::NodeHandle nh;

#define LOOPTIME 10

Motor right(11,10,20,21);
Motor left(9,8,18,19);
Motor right(11,10,20,21); //Motor1, Motor2, Encoder A, Encoder B
Motor left(9,8,18,19); //Motor1, Motor2, Encoder A, Encoder B

volatile long encoder0Pos = 0; // encoder 1
volatile long encoder1Pos = 0; // encoder 2
Expand Down Expand Up @@ -73,10 +74,10 @@ void setup() {
leftPID.SetOutputLimits(-100, 100);

// Serial.println("Basic Encoder Test:");
attachInterrupt(digitalPinToInterrupt(left.en_a), change_left_a, CHANGE);
attachInterrupt(digitalPinToInterrupt(left.en_b), change_left_b, CHANGE);
attachInterrupt(digitalPinToInterrupt(right.en_a), change_right_a, CHANGE);
attachInterrupt(digitalPinToInterrupt(right.en_b), change_right_b, CHANGE);
attachInterrupt(digitalPinToInterrupt(left.enc_a), change_left_a, CHANGE);
attachInterrupt(digitalPinToInterrupt(left.enc_b), change_left_b, CHANGE);
attachInterrupt(digitalPinToInterrupt(right.enc_a), change_right_a, CHANGE);
attachInterrupt(digitalPinToInterrupt(right.enc_b), change_right_b, CHANGE);
}

void loop() {
Expand Down Expand Up @@ -113,7 +114,7 @@ void loop() {
left.rotate(left_output);
rightPID.Compute();
right.rotate(right_output);
// Serial.print(encoder0Pos);
// Serial.print(encoder0Pos); //un-comment this line and the next 2 to have encoder position written to the serial output
// Serial.print(",");
// Serial.println(encoder1Pos);
}
Expand Down Expand Up @@ -141,9 +142,9 @@ void publishSpeed(double time) {
void change_left_a(){

// look for a low-to-high on channel A
if (digitalRead(left.en_a) == HIGH) {
if (digitalRead(left.enc_a) == HIGH) {
// check channel B to see which way encoder is turning
if (digitalRead(left.en_b) == LOW) {
if (digitalRead(left.enc_b) == LOW) {
encoder0Pos = encoder0Pos + 1; // CW
}
else {
Expand All @@ -153,7 +154,7 @@ void change_left_a(){
else // must be a high-to-low edge on channel A
{
// check channel B to see which way encoder is turning
if (digitalRead(left.en_b) == HIGH) {
if (digitalRead(left.enc_b) == HIGH) {
encoder0Pos = encoder0Pos + 1; // CW
}
else {
Expand All @@ -166,9 +167,9 @@ void change_left_a(){
void change_left_b(){

// look for a low-to-high on channel B
if (digitalRead(left.en_b) == HIGH) {
if (digitalRead(left.enc_b) == HIGH) {
// check channel A to see which way encoder is turning
if (digitalRead(left.en_a) == HIGH) {
if (digitalRead(left.enc_a) == HIGH) {
encoder0Pos = encoder0Pos + 1; // CW
}
else {
Expand All @@ -178,7 +179,7 @@ void change_left_b(){
// Look for a high-to-low on channel B
else {
// check channel B to see which way encoder is turning
if (digitalRead(left.en_a) == LOW) {
if (digitalRead(left.enc_a) == LOW) {
encoder0Pos = encoder0Pos + 1; // CW
}
else {
Expand All @@ -194,9 +195,9 @@ void change_left_b(){
void change_right_a(){

// look for a low-to-high on channel A
if (digitalRead(right.en_a) == HIGH) {
if (digitalRead(right.enc_a) == HIGH) {
// check channel B to see which way encoder is turning
if (digitalRead(right.en_b) == LOW) {
if (digitalRead(right.enc_b) == LOW) {
encoder1Pos = encoder1Pos - 1; // CW
}
else {
Expand All @@ -206,7 +207,7 @@ void change_right_a(){
else // must be a high-to-low edge on channel A
{
// check channel B to see which way encoder is turning
if (digitalRead(right.en_b) == HIGH) {
if (digitalRead(right.enc_b) == HIGH) {
encoder1Pos = encoder1Pos - 1; // CW
}
else {
Expand All @@ -219,9 +220,9 @@ void change_right_a(){
void change_right_b(){

// look for a low-to-high on channel B
if (digitalRead(right.en_b) == HIGH) {
if (digitalRead(right.enc_b) == HIGH) {
// check channel A to see which way encoder is turning
if (digitalRead(right.en_a) == HIGH) {
if (digitalRead(right.enc_a) == HIGH) {
encoder1Pos = encoder1Pos - 1; // CW
}
else {
Expand All @@ -231,7 +232,7 @@ void change_right_b(){
// Look for a high-to-low on channel B
else {
// check channel B to see which way encoder is turning
if (digitalRead(right.en_a) == LOW) {
if (digitalRead(right.enc_a) == LOW) {
encoder1Pos = encoder1Pos - 1; // CW
}
else {
Expand Down

0 comments on commit 5b7e23d

Please sign in to comment.