#include "Arduino.h"
#include "Mycar.h"
int speedmotorLeft = 255;
int speedmotorRight = 255;
Mycar::Mycar(int leftFront1, int leftFront2, int leftBack1, int leftBack2,
int rightFront1, int rightFront2, int rightBack1, int rightBack2){
pinMode(leftFront1,OUTPUT);
pinMode(leftFront2,OUTPUT);
pinMode(leftBack1,OUTPUT);
pinMode(leftBack2,OUTPUT);
pinMode(rightFront1,OUTPUT);
pinMode(rightFront2,OUTPUT);
pinMode(rightBack1,OUTPUT);
pinMode(rightBack2,OUTPUT);
_leftFront1 = leftFront1;
_leftFront2 = leftFront2;
_leftBack1 =leftBack1;
_leftBack2 =leftBack2;
_rightFront1 = rightFront1;
_rightFront2 = rightFront2;
_rightBack1 =rightBack1;
_rightBack2 =rightBack2;
}
void Mycar:: setMaxSpeed(int both){
setMaxLeftSpeed(both);
setMaxRightSpeed(both);
}
void Mycar:: setMaxSpeed(int left,int right){
setMaxLeftSpeed(left);
setMaxRightSpeed(right);
}
void Mycar:: setMaxLeftSpeed(int left){
speedmotorLeft = left;
}
void Mycar:: setMaxRightSpeed(int right){
speedmotorRight = right;
}
void Mycar:: rightMotor(char mag){
int actualspeed = 0 ;
if(mag > 0){
float ratio = (float) mag/128;
actualspeed = (int) (ratio*speedmotorRight);
analogWrite(_rightFront1,actualspeed);
analogWrite(_rightBack1,actualspeed);
digitalWrite(_rightFront2,LOW);
digitalWrite(_rightBack2,LOW);
}
else if(mag == 0){
stopRight();
}
else{
float ratio = (float) abs (mag)/128;
actualspeed = (int) (ratio*speedmotorRight);
analogWrite(_rightFront2,actualspeed);
analogWrite(_rightBack2,actualspeed);
digitalWrite(_rightFront1,LOW);
digitalWrite(_rightBack1,LOW);
}
}
void Mycar:: leftMotor(char mag){
int actualspeed = 0 ;
if(mag > 0){
float ratio = (float) mag/128;
actualspeed = (int) (ratio*speedmotorLeft);
analogWrite(_leftFront1,actualspeed);
analogWrite(_leftBack1,actualspeed);
digitalWrite(_leftFront2,LOW);
digitalWrite(_leftBack2,LOW);
}
else if(mag == 0){
stopLeft();
}
else{
float ratio = (float) abs (mag)/128;
actualspeed = (int) (ratio*speedmotorLeft);
analogWrite(_leftFront2,actualspeed);
analogWrite(_leftBack2,actualspeed);
digitalWrite(_leftFront1,LOW);
digitalWrite(_leftBack1,LOW);
}
}
void Mycar:: drive(char mag1,char mag2){
leftMotor(mag1);
rightMotor(mag2);
}
void Mycar:: forward(){
leftMotor(127);
rightMotor(127);
}
void Mycar:: backward(){
leftMotor(-128);
rightMotor(-128);
}
void Mycar:: stopcar(){
stopLeft();
stopRight();
}
void Mycar:: stopLeft(){
analogWrite(_leftFront1,LOW);
analogWrite(_leftFront2,LOW);
analogWrite(_leftBack1,LOW);
analogWrite(_leftBack2,LOW);
}
void Mycar:: stopRight(){
analogWrite(_rightFront1,LOW);
analogWrite(_rightFront2,LOW);
analogWrite(_rightBack1,LOW);
analogWrite(_rightBack2,LOW);
}
void Mycar:: fastStopLeft(){
analogWrite(_leftFront1,HIGH);
analogWrite(_leftFront2,HIGH);
analogWrite(_leftBack1,HIGH);
analogWrite(_leftBack2,HIGH);
}
void Mycar:: fastStopRight(){
analogWrite(_rightFront1,HIGH);
analogWrite(_rightFront2,HIGH);
analogWrite(_rightBack1,HIGH);
analogWrite(_rightBack2,HIGH);
}
void Mycar:: fastStop(){
fastStopRight();
fastStopLeft();
}