Posts Tagged ‘Motor control’

New code for the motor part of the X-bot

Posted in Arduino, Processing, Self balancing robot on April 22nd, 2011 by x-firm – Comments Off

I have recoded the motor part and added the encoder for the other motor and made a PID for each motor that takes the output from the current PID. This for trying to get the two motors to behave equal. The original PID is only looking on the right motor encoder as before. But I’m calculating the current speed in pulses/10ms for each motor and then using that and the output from the old PID to control the motors for a requested speed in pulses/10ms..

That feels better than just sending a value of 0-255 that has no connection to the speed of the motor that are depending on the surface and battery level.

I have made a new sketch for the bot and a GUI to make settings and testing the motor PIDs you can download it from this links:
Motor_PID_Enc_v2 (Bot code)
Motor_PID_Enc_v2 (GUI)

Calibrating/testing the motors and encoders..

Posted in Arduino, Processing, Self balancing robot on November 24th, 2010 by x-firm – Be the first to comment

I started to check the differences of the motors by using the encoders to try to see the distance the motors turned in a constant time and get a factor for the diff. I drive the motors in both directions in four different speeds 50, 100, 200, 250..

I made a sketch for the Arduino and a GUI sketch in processing based on the Balancing Bot GUI, and thought that this cant be so hard to do just see the diff. and calculate a factor for the faster motor but that was not the case..

The first run gave me the results like in the image below, where the motors behaved very different in forward to backward motion. When going forward for a time constant(2000ms) and then sending the drive_motor(0) the motor continued running in free spin for a short while. But when running backward the motor brakes for a short while.

Click for larger image

Speed   L           R

255    7662   :  7413

-255   -5516  :  -5541

150    6582   :  6386

-150   -4901  :  -4872

50     3342     :  3291

-50    -2747   :  -2705

As you can see the behavior is very different in the two directions..

I changed the drive_motor function like below and tried again and the result was better but is I going about this in the right way?

int Drive_Motor(int torque)  {
  if (torque > 0)  {
    // drive motors forward
    digitalWrite(InA_R, LOW);
    digitalWrite(InB_R, HIGH);
    digitalWrite(InA_L, LOW);
    digitalWrite(InB_L, HIGH);
    forward = true;
  }else if(torque < 0) {     // drive motors backward
    digitalWrite(InB_R, LOW);
    digitalWrite(InA_R, HIGH);
    digitalWrite(InB_L, LOW);
    digitalWrite(InA_L, HIGH);
    torque = abs(torque);
    forward = false;
  }else{
    if(forward){
      digitalWrite(InA_R, HIGH);
      digitalWrite(InB_R, LOW);
      digitalWrite(InA_L, HIGH);
      digitalWrite(InB_L, LOW);
    }else{
      digitalWrite(InA_R, LOW);
      digitalWrite(InB_R, HIGH);
      digitalWrite(InA_L, LOW);
      digitalWrite(InB_L, HIGH);
    }
  }
  //if(torque>5) map(torque,0,255,30,255);
    analogWrite(PWM_R,torque * motorOffsetR);
    analogWrite(PWM_L,torque * motorOffsetL);
    Serial.println(torque,DEC);
}

Now it looks like the Arduino and the motor controller is behaving in the same way in both directions. I need to take some more readings to see if the differences that are left are linear in some way.. It feels like there are a difference between the motors in both directions but also that both motors are going faster forward, and that I think is created by the motor control??..

See image below..

Click for larger image

Heres the Arduino sketch I used..

Heres the Processing sketch I used..

The main part of the Arduino sketch:

// KasBot Encoder test V1  -  Main module       basic version, angles in Quids, 10 bit ADC
/*
  Description:
  The KasBot Encoder test Vx is made for checking that the encoder signal workes and
  to tune the diffrenses from your motors..

  This code is aimed for the Encoder test GUI v1.0

  Version log:

  v1.0  -

*/

#define   InA_R          6                      // INA right motor pin
#define   InB_R          7                      // INB right motor pin
#define   PWM_R          10                     // PWM right motor pin
#define   InA_L          8                      // INA left motor pin
#define   InB_L          9                      // INB left motor pin
#define   PWM_L          11                     // PWM left motor pin
#define encodPinA_R      3                      // encoder A pin left motor
#define encodPinB_R      5                      // encoder B pin right motor
#define encodPinA_L      2                      // encoder A pin left motor
#define encodPinB_L      12                     // encoder B pin right motor

#define LOOPTIME         100                    // PID loop time
#define FORWARD          1                      // direction of rotation
#define BACKWARD         2                      // direction of rotation

#define DELAY_TIME       5000                   //Time to delay after motion
#define RUN_TIME         2000                   //Time to run motor

int speeds[] = {50, 100, 200, 255};
int speedIndex = 0;

int STD_LOOP_TIME  =  9;             

int lastLoopTime = STD_LOOP_TIME;
int lastLoopUsefulTime = STD_LOOP_TIME;
unsigned long loopStartTime = 0;

unsigned long delayStart = 0;

long count_R = 0;                                 // rotation counter right motor
long count_L = 0;                                 // rotation counter left motor

boolean frwMotion = true;                         // motor moves

void setup() {
  pinMode(InA_R, OUTPUT);
  pinMode(InB_R, OUTPUT);
  pinMode(PWM_R, OUTPUT);
  pinMode(InA_L, OUTPUT);
  pinMode(InB_L, OUTPUT);
  pinMode(PWM_L, OUTPUT);

  pinMode(encodPinA_R, INPUT);
  pinMode(encodPinB_R, INPUT);
  digitalWrite(encodPinA_R, HIGH);                      // turn on pullup resistor
  digitalWrite(encodPinB_R, HIGH);
  attachInterrupt(1, rencoder_R, FALLING);

  pinMode(encodPinA_L, INPUT);
  pinMode(encodPinB_L, INPUT);
  digitalWrite(encodPinA_L, HIGH);                      // turn on pullup resistor
  digitalWrite(encodPinB_L, HIGH);
  attachInterrupt(0, rencoder_L, FALLING);

  Serial.begin(19200);
}

void loop() {
// ********* Simple motor test for serial monitor ***********************

  //motorDebugForSerialMonitor();

// *********************** Motor drive **********************************
  //Turns motors on for RUN_TIME and then off for DELAY_TIME
  if((millis() - delayStart) <= RUN_TIME){
    if(frwMotion){
      Drive_Motor(speeds[speedIndex]);
    }else{
      Drive_Motor((speeds[speedIndex] * (-1)));
    }
  }else if((millis() - delayStart) > RUN_TIME){
    Drive_Motor(0);
  }

  if((millis() - delayStart) >= (RUN_TIME + DELAY_TIME)){
    delayStart = millis();
    if(frwMotion){
      frwMotion = false;
    }else{
      speedIndex++;
      frwMotion = true;
    }
    clearCounts();
    if(speedIndex >= 3) speedIndex=0;
  }

 // *********************** print Debug info *****************************
  serialIn_GUI();       //Processing information from a pc
  serialOut_GUI();	//Sending information to pc for debug

 // *********************** loop timing control **************************
  lastLoopUsefulTime = millis()-loopStartTime;
  if(lastLoopUsefulTime<STD_LOOP_TIME)         delay(STD_LOOP_TIME-lastLoopUsefulTime);
  lastLoopTime = millis() - loopStartTime;
  loopStartTime = millis();

}

void clearCounts(){
  count_L = 0;
  count_R = 0;
}

void motorDebugForSerialMonitor()
{
  Drive_Motor(255);
  delay(2000);
  Drive_Motor(0);
  delay(500);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  Drive_Motor(-255);
  delay(2000);
  Drive_Motor(0);
  delay(500);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  Drive_Motor(150);
  delay(2000);
  Drive_Motor(0);
  delay(500);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  Drive_Motor(-150);
  delay(2000);
  Drive_Motor(0);
  delay(500);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  Drive_Motor(50);
  delay(2000);
  Drive_Motor(0);
  delay(500);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  Drive_Motor(-50);
  delay(2000);
  Drive_Motor(0);
  delay(2000);
  Serial.print(count_L,DEC);
  Serial.print(" : ");
  Serial.println(count_R,DEC);
  clearCounts();
  delay(4500);

  while(true){delay(100);}
}