Toy Car Power Wheels Part 4

Toy Car Power Wheels Part 4

Aug 30, 2019

John Praleston


Final gas pedal prints installed. Gear is installed onto the potentiometer with throttle arm pressed against it. The mounting bracket is bolted directly into the car chassis. A stop screw was installed to have a constant limited travel so there would be constant values to the Arduino.

 

The steering potentiometer was installed into the final steering mount with an arm connected to the steering linkage.

 

To tighten up the steering linkage even more, a bracket with two bearings installed was pressed onto the steering linkage. 

A sleeve was installed around the steering output to remove the slack from the output motor to the steering arm.

 

Overview of the installed 3d printed system (not including steering arm)

3D printed steering arm pressed onto steering potentiometer, resting around steering linkage

 

L298 dual Hbridge controller – Used for forward/reverse function of drive motors as well as left/right function of steering motor.

Remote/Manual switch required rewiring to send proper signal to Arduino. Ground removed and direct wire back to Arduino installed (Green)

Overhead view of all wiring installed for testing

Master switch installed – wiring allows for charging while all components are off

Underside all wired  - Both potentiometer voltages are ran directly from the Arduino 3.3V/5V ports. Each has their own circuit due to issues from sharing voltage circuits (See video tests from powering Arduino from battery vs voltage regulator)

Electronics box printed and inserts installed (see video of insert installation)

 

Hardware used for installation or electronics box

Inserts used for electronics box – 3mm

Inserts used for electronics box – 3mm

Components installed in electronics box (updated installation moves on L298 H-bridge to 2nd level)

Updated installation, Radio reciever in place of L298 (for space and wiring purposes)

2nd level mounted – 2 voltage regulators, 1 H-bridge (Hole had to be drilled for power wire to Arduino due to limited length)

Top cover of electronics box installed

 

Electronics box completed and installed

Final picture of underside and wiring (red wires crossing go to master switch installed)

Top side picture – only difference from stock is the red master switch located on left of driver

 

Major lessons in wiring

Potentiometers required individual circuits to avoid varying readings from Arduino

Arduino cannot read signals from 12V signals – used 5/3.3V

Analog pins can read digital signals (ran out of digital ports)

See wiring diagram below for full overview of new wiring

 

Car is currently operating correctly

Remote Mode

  • Throttle forward/reverse controlled by Traxxas controller
  • Steering left/right controlled by Traxxas Controller
  • Steering auto center (position guided by potentiometer)

Manual Mode

  • Steering Open
  • Throttle position determined by gas pedal potentiometer
  • Forward/reverse switch from shifter lever

Master switch

  • Controls power to all electronic components except charging unit

 

 

Final Code after Update – Fixed return to center steering issue

 

// MANUAL VS REMOTE INT

const int  buttonPinRM = 11;    // the pin that the pushbutton is attached to

int buttonStateRM = 0;         // current state of the button

 

// FORWARD VS REMOTE INT

const int  buttonPinFR = 12;    // the pin that the pushbutton is attached to

int buttonStateFR = 0;         // current state of the button

 

// Motor Left

int en1 = 10;

int in1 = 9;

int in2 = 8;

 

// Motor Right

int en2 = 5;

int in3 = 6;

int in4 = 7;

 

// Motor Speed Values - Start at zero

int MotorSpeed1 = 0;

int MotorSpeed2 = 0;

 

//Traxxis Controller

//Throttle

byte THROTTLE_PIN = A5;

int pwm_value_t;

//Steering

byte STEERING_PIN = A4;

int pwm_value_s;

 

// Motor Steering

 

int en1s = 3;

int in1s = 2;

int in2s = 4;

int MotorSpeed3 = 0;

int InputValue;

int SteeringAngle;

int Pcontroller;

int Position;

 

 

void setup() {

 

  // initialize serial communication:

  Serial.begin(9600);

 

  // initialize the manual remote pin as a input: 11

  pinMode(buttonPinRM, INPUT);

 

  // initialize the forward reverse pin as a input: 12

  pinMode(buttonPinFR, INPUT);

 

  // Set all the motor control pins to outputs

  pinMode(en1, OUTPUT);

  pinMode(in1, OUTPUT);

  pinMode(in2, OUTPUT);

  pinMode(en2, OUTPUT);

  pinMode(in3, OUTPUT);

  pinMode(in4, OUTPUT);

  pinMode(STEERING_PIN, INPUT);

  pinMode(en1s, OUTPUT);

  pinMode(in1s, OUTPUT);

  pinMode(in2s, OUTPUT);

 

  // Start with motors disabled and direction forward

 

  // Motor Left

  digitalWrite(en1, LOW);

  digitalWrite(in1, HIGH);

  digitalWrite(in2, LOW);

 

  // Motor Right

  digitalWrite(en2, LOW);

  digitalWrite(in3, HIGH);

  digitalWrite(in4, LOW);

 

  // Motor Steering

  digitalWrite(en1s, LOW);

  digitalWrite(in1s, HIGH);

  digitalWrite(in2s, LOW);

}

 

 

 

 

 

 

 

void loop() {

 

//REMOTE VS MANUAL

//REMOTE = THROTTLE AND STEERING CONTROLLED BY TRAXXAS CONTROLLER

//MANAUL = THROTTLE CONTROLLED BY GAS PEDAL, STEERING MOTOR OFF

 

  // read the manual vs remote input pin:

  buttonStateRM = digitalRead(buttonPinRM);

 

  // read the forward reverse input pin:

  buttonStateFR = digitalRead(buttonPinFR);

 

// MANUAL MODE //

 

  // -----MANUAL MODE-----

  if (buttonStateRM == HIGH) {

//  Serial.println("Manual");

 

// read the input value for gas pedal:

  int sensorValueG = analogRead(A0);

 

  digitalWrite(in1s, HIGH);

  digitalWrite(in2s, LOW);

 

  if (buttonStateFR == HIGH) {

//  Serial.print("\t");

//  Serial.println("Forward");

     

  digitalWrite(in1, HIGH);

  digitalWrite(in2, LOW);

  digitalWrite(in3, HIGH);

  digitalWrite(in4, LOW);

}

  if (buttonStateFR == LOW) {

// Serial.print("\t");

// Serial.println("Reverse");

 

  digitalWrite(in1, LOW);

  digitalWrite(in2, HIGH);

  digitalWrite(in3, LOW);

  digitalWrite(in4, HIGH);     

    }

   

delay(5);

  // Gas Pedal Value Map

  sensorValueG = map(sensorValueG, 343, 790, 0, 255);

  MotorSpeed3 = 0;

  if (sensorValueG < 10)sensorValueG = 0;

  analogWrite(en1, sensorValueG);

  analogWrite(en2, sensorValueG);

  analogWrite(en1s, MotorSpeed3);

  }

 

 

 

 

 

// REMOTE MODE //

 

// -----REMOTE MODE-----

 

  if (buttonStateRM == LOW) {

   

// Serial.println("Remote");

 

  // Read Steering Output from Traxxas Controller - Values (Left full 1960, Right full 980)

 

  // Steering Angle

  int sensorValueS = analogRead(A1);

  SteeringAngle = map(sensorValueS, 500, 665, 0, 1000);

  if (SteeringAngle < 510 && SteeringAngle > 500)SteeringAngle = 500;

 

  // Traxxas Position

  pwm_value_s = pulseIn(STEERING_PIN, HIGH);

  InputValue = map(pwm_value_s, 1960, 990, 0, 1000);

  if (InputValue < 530 && InputValue > 470)InputValue = 500;

 

  // Turn or not to turn

  Pcontroller=abs(InputValue-SteeringAngle);

 

  Position = (InputValue-SteeringAngle);

 

if(Pcontroller < 30)MotorSpeed3 = 0;

 

int PConstant = 7;

 

 

//------Steering------// Needs tuning

if(Pcontroller > 30)

{

 

if (Position > 0)

  {

    // This is Right

    digitalWrite(in1s, LOW);

    digitalWrite(in2s, HIGH);

 

    // Motor Speed - needs tune

    MotorSpeed3 = map(Pcontroller * PConstant, 0, 1000, 0, 255);

  }

  else if (Position < 0)

  {

    // This is Left

    digitalWrite(in1s, HIGH);

    digitalWrite(in2s, LOW);

 

    //Motor Speed - needs tune

    MotorSpeed3 = map(Pcontroller * PConstant, 0, 1000, 0, 255);

  }

 

  else

  {

    // Stopped

    MotorSpeed3 = 0;

  }

}

  if (MotorSpeed3 > 255)MotorSpeed3 = 255;

  if (MotorSpeed3 < 30)MotorSpeed3 = 0;

 

   // Send Motorspeed to Motor

 analogWrite(en1s, MotorSpeed3);

 delay(1);

 

  Serial.println(Pcontroller);

  Serial.print("\t");

  Serial.println(InputValue);

  Serial.print("\t\t");

  Serial.println(SteeringAngle);

  Serial.print("\t\t\t");

  Serial.println(Position);

  Serial.print("\t\t\t\t");

  Serial.println(MotorSpeed3);

 

//------THROTTLE------//

 

 

 

 

  // Read Throttle Output from Traxxas Controller - Values (Full Back 1960, Full Forward 980)

  pwm_value_t = pulseIn(THROTTLE_PIN, HIGH);

 

 

 

 

 

 

  if (pwm_value_t < 1400)

  {

    // This is Backward

 

    // Set Motor Left backward

    digitalWrite(in1, LOW);

    digitalWrite(in2, HIGH);

 

    // Set Motor Right Backward

    digitalWrite(in3, LOW);

    digitalWrite(in4, HIGH);

 

    //Determine Motor Speeds

    MotorSpeed1 = map(pwm_value_t, 1400, 990, 0, 255);

 

  }

  else if (pwm_value_t > 1550)

  {

    // This is Forward

 

    // Set Motor Left forward

    digitalWrite(in1, HIGH);

    digitalWrite(in2, LOW);

 

    // Set Motor Right Forward

    digitalWrite(in3, HIGH);

    digitalWrite(in4, LOW);

 

    //Determine Motor Speeds

    MotorSpeed1 = map(pwm_value_t, 1550, 1960, 0, 255);

    }   

 

  else

  {

    // This is Stopped

    MotorSpeed1 = 0;

  }

 

  if (MotorSpeed1 < 10)MotorSpeed1 = 0;  

  if (MotorSpeed1 > 255)MotorSpeed1 = 255;

  

 

  // Set the motor speeds

  analogWrite(en1, MotorSpeed1);

  analogWrite(en2, MotorSpeed1);

  delay(5);

 

// Serial.print("\t\t");

// Serial.print(MotorSpeed1);

 

    }

}

 

Tags

Archives