Lesson 6: Move control-PID Control for 2 motor

Ros_arduino_bridge the base controller in the PID control of the two motors is a set of PID parameters, but the actual use, due to the characteristics of the motor, terrain, or robot load balance of the many problems so that the robot can not follow the scheduled trajectory , The simplest is whether the robot can go straight, which requires the two motors were PID speed, this section will be modified ros_arduino_bridge to support the two motor with different PID parameters speed

1.First modify the arduino code

1.1.diff_controller.h
Increase the PID control variables of the left and right motors:

/* PID Parameters */
int Kp = 20;
int Kd = 12;
int Ki = 0;
int Ko = 50;

int left_Kp=Kp;
int left_Kd=Kd;
int left_Ki=Ki;
int left_Ko=Ko;

int right_Kp=Kp;
int right_Kd=Kd;
int right_Ki=Ki;
int right_Ko=Ko;

modify resetPID function

void resetPID(){
 leftPID.TargetTicksPerFrame = 0.0;
 leftPID.Encoder = readEncoder(LEFT);
 leftPID.PrevEnc = leftPID.Encoder;
 leftPID.output = 0;
 leftPID.PrevInput = 0;
 leftPID.ITerm = 0;

 rightPID.TargetTicksPerFrame = 0.0;
 rightPID.Encoder = readEncoder(RIGHT);
 rightPID.PrevEnc = rightPID.Encoder;
 rightPID.output = 0;
 rightPID.PrevInput = 0;
 rightPID.ITerm = 0;
}

Define the dorightPID () and doleftPID () functions of the left and right motors, respectively

/* PID routine to compute the next motor commands */
void dorightID(SetPointInfo * p) {
  long Perror;
  long output;
  int input;

  //Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc);
  input = p->Encoder - p->PrevEnc;
  Perror = p->TargetTicksPerFrame - input;

  /*
  * Avoid derivative kick and allow tuning changes,
  * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/
  * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
  */
  //output = (Kp * Perror + Kd * (Perror - p->PrevErr) + Ki * p->Ierror) / Ko;
  // p->PrevErr = Perror;
  output = (right_Kp * Perror - right_Kd * (input - p->PrevInput) + p->ITerm) / right_Ko;
  p->PrevEnc = p->Encoder;

  output += p->output;
  // Accumulate Integral error *or* Limit output.
  // Stop accumulating when output saturates
  if (output >= MAX_PWM)
    output = MAX_PWM;
  else if (output <= -MAX_PWM)
    output = -MAX_PWM;
  else
  /*
  * allow turning changes, see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
  */
    p->ITerm += Ki * Perror;

  p->output = output;
  p->PrevInput = input;
}

/* PID routine to compute the next motor commands */
void doleftPID(SetPointInfo * p) {
  long Perror;
  long output;
  int input;

  //Perror = p->TargetTicksPerFrame - (p->Encoder - p->PrevEnc);
  input = p->Encoder - p->PrevEnc;
  Perror =p->TargetTicksPerFrame + input;

  /*
  * Avoid derivative kick and allow tuning changes,
  * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-derivative-kick/
  * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
  */
  //output = (Kp * Perror + Kd * (Perror - p->PrevErr) + Ki * p->Ierror) / Ko;
  // p->PrevErr = Perror;
  output = (left_Kp * Perror - left_Kd * (input - p->PrevInput) + p->ITerm) / left_Ko;
  p->PrevEnc = p->Encoder;

  output += p->output;
  // Accumulate Integral error *or* Limit output.
  // Stop accumulating when output saturates
  if (output >= MAX_PWM)
    output = MAX_PWM;
  else if (output <= -MAX_PWM)
    output = -MAX_PWM;
  else
  /*
  * allow turning changes, see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-tuning-changes/
  */
    p->ITerm += Ki * Perror;

  p->output = output;
  p->PrevInput = input;
}

modify updatePID() function

void updatePID() {
  /* Read the encoders */
  leftPID.Encoder =readEncoder(LEFT);
  rightPID.Encoder = readEncoder(RIGHT);

  /* If we're not moving there is nothing more to do */
  if (!moving){
    /*
    * Reset PIDs once, to prevent startup spikes,
    * see http://brettbeauregard.com/blog/2011/04/improving-the-beginner%E2%80%99s-pid-initialization/
    * PrevInput is considered a good proxy to detect
    * whether reset has already happened
    */
    if (leftPID.PrevInput != 0 || rightPID.PrevInput != 0) resetPID();
    return;
  }

  /* Compute PID update for each motor */
  dorightID(&rightPID);
  doleftPID(&leftPID);

  /* Set the motor speeds accordingly */
  setMotorSpeeds(leftPID.output, rightPID.output);

}

1.2. encoder_driver.ino

Since the direction of rotation of the left and right motors is reversed, there will be an increase in the reading of the encoder, but when we actually control, the direction of travel of the two motors is the same, which affects the PID calculation. Need to reverse the encoder on the left side of the motor read, modify the readEncoder function.

 /* Wrap the encoder reading function */
 long readEncoder(int i) {
 if (i == LEFT) return 0-left_enc_pos;
 else return right_enc_pos;
 }

1.3.ROSArduinoBridge.ino

Modify the declaration of pid_args to the following code

int pid_args[8];

Modify the runCommand () function, modify the case UPDATE_PID, the original Kp, Kd, Ki, Ko assignment code comment out, modify the following code

    case UPDATE_PID:
      while ((str = strtok_r(p, ":", &p)) != '\0') {
        pid_args[i] = atoi(str);
        i++;
      }
//      Kp = pid_args[0];
//      Kd = pid_args[1];
//      Ki = pid_args[2];
//      Ko = pid_args[3];

      left_Kp = pid_args[0];
      left_Kd = pid_args[1];
      left_Ki = pid_args[2];
      left_Ko = pid_args[3];

      right_Kp = pid_args[4];
      right_Kd = pid_args[5];
      right_Ki = pid_args[6];
      right_Ko = pid_args[7];
      Serial.println("OK");
      break;

Now arduino side has been supported on the two motors using different PID parameters of the speed control

1.4ROSArduinoBridge.ino

Modify the file argv1 argv2 two parameters of the definition of its array length expansion, because these two parameters used to receive the host computer to send the command, we increased the pid parameters, making the command length exceeds the original two parameters length.
// Character arrays to hold the first and second arguments
char argv1[32];
char argv2[32];

2.Modify ROS package code

2.1.my_arduino_params.yaml
Increase the PID parameters of the left and right motors in the PID parameter section

# === PID parameters
Kp: 10
Kd: 12
Ki: 0
Ko: 50
accel_limit: 1.0

left_Kp: 10
left_Kd: 12
left_Ki: 0
left_Ko: 50

right_Kp: 8
right_Kd: 12
right_Ki: 0

2.2.arduino_driver.py

modify update_pid function

def update_pid(self, left_Kp, left_Kd, left_Ki, left_Ko, right_Kp, right_Kd, right_Ki, right_Ko):
        ''' Set the PID parameters on the Arduino
        '''
        print "Updating PID parameters"
        cmd = 'u ' + str(left_Kp) + ':' + str(left_Kd) + ':' + str(left_Ki) + ':' + str(left_Ko) + ':' + str(right_Kp) + ':' + str(right_Kd) + ':' + str(right_Ki) + ':' + str(right_Ko)
        self.execute_ack(cmd)  

2.3.base_controller.py

modify def init(self, arduino, base_frame),Increase the initialization code of the left and right motor PID parameters

def __init__(self, arduino, base_frame):
        self.arduino = arduino
        self.base_frame = base_frame
        self.rate = float(rospy.get_param("~base_controller_rate", 10))
        self.timeout = rospy.get_param("~base_controller_timeout", 1.0)
        self.stopped = False

        pid_params = dict()
        pid_params['wheel_diameter'] = rospy.get_param("~wheel_diameter", "") 
        pid_params['wheel_track'] = rospy.get_param("~wheel_track", "")
        pid_params['encoder_resolution'] = rospy.get_param("~encoder_resolution", "") 
        pid_params['gear_reduction'] = rospy.get_param("~gear_reduction", 1.0)

        #modify by william 
        pid_params['left_Kp'] = rospy.get_param("~left_Kp", 20)
        pid_params['left_Kd'] = rospy.get_param("~left_Kd", 12)
        pid_params['left_Ki'] = rospy.get_param("~left_Ki", 0)
        pid_params['left_Ko'] = rospy.get_param("~left_Ko", 50)
        pid_params['right_Kp'] = rospy.get_param("~right_Kp", 20)
        pid_params['right_Kd'] = rospy.get_param("~right_Kd", 12)
        pid_params['right_Ki'] = rospy.get_param("~right_Ki", 0)
        pid_params['right_Ko'] = rospy.get_param("~right_Ko", 50)

        self.accel_limit = rospy.get_param('~accel_limit', 0.1)
        self.motors_reversed = rospy.get_param("~motors_reversed", False)

        # Set up PID parameters and check for missing values
        self.setup_pid(pid_params)

        # How many encoder ticks are there per meter?
        self.ticks_per_meter = self.encoder_resolution * self.gear_reduction  / (self.wheel_diameter * pi)

        # What is the maximum acceleration we will tolerate when changing wheel speeds?
        self.max_accel = self.accel_limit * self.ticks_per_meter / self.rate

        # Track how often we get a bad encoder count (if any)
        self.bad_encoder_count = 0

        now = rospy.Time.now()    
        self.then = now # time for determining dx/dy
        self.t_delta = rospy.Duration(1.0 / self.rate)
        self.t_next = now + self.t_delta

        # internal data        
        self.enc_left = None            # encoder readings
        self.enc_right = None
        self.x = 0                      # position in xy plane
        self.y = 0
        self.th = 0                     # rotation in radians
        self.v_left = 0
        self.v_right = 0
        self.v_des_left = 0             # cmd_vel setpoint
        self.v_des_right = 0
        self.last_cmd_vel = now

        # subscriptions
        rospy.Subscriber("cmd_vel", Twist, self.cmdVelCallback)

        # Clear any old odometry info
        self.arduino.reset_encoders()

        # Set up the odometry broadcaster
        self.odomPub = rospy.Publisher('odom', Odometry)
        self.odomBroadcaster = TransformBroadcaster()

        rospy.loginfo("Started base controller for a base of " + str(self.wheel_track) + "m wide with " + str(self.encoder_resolution) + " ticks per rev")
        rospy.loginfo("Publishing odometry data at: " + str(self.rate) + " Hz using " + str(self.base_frame) + " as base frame")

修改def setup_pid(self, pid_params):

def setup_pid(self, pid_params):
        # Check to see if any PID parameters are missing
        missing_params = False
        for param in pid_params:
            if pid_params[param] == "":
                print("*** PID Parameter " + param + " is missing. ***")
                missing_params = True

        if missing_params:
            os._exit(1)

        self.wheel_diameter = pid_params['wheel_diameter']
        self.wheel_track = pid_params['wheel_track']
        self.encoder_resolution = pid_params['encoder_resolution']
        self.gear_reduction = pid_params['gear_reduction']

        #self.Kp = pid_params['Kp']
        #self.Kd = pid_params['Kd']
        #self.Ki = pid_params['Ki']
        #self.Ko = pid_params['Ko']

        #self.arduino.update_pid(self.Kp, self.Kd, self.Ki, self.Ko)

        #modify by william
        self.left_Kp = pid_params['left_Kp']
        self.left_Kd = pid_params['left_Kd']
        self.left_Ki = pid_params['left_Ki']
        self.left_Ko = pid_params['left_Ko']

        self.right_Kp = pid_params['right_Kp']
        self.right_Kd = pid_params['right_Kd']
        self.right_Ki = pid_params['right_Ki']
        self.right_Ko = pid_params['right_Ko']

        #Pass the 8 parameters to the update_pid function
        self.arduino.update_pid(self.left_Kp, self.left_Kd, self.left_Ki, self.left_Ko, self.right_Kp, self.right_Kd, self.right_Ki, self.right_Ko)

After modifying the above code ros_arduino_bridge can be set on the two different PID parameters of the motor speed control.

3.PID Speed control

Two motor PID speed is more trouble, need to constantly modify the parameters of the corresponding parameters, so that the speed of the two motors can be consistent, the author’s experience is to debug a good side of the motor, in this motor as the subject matter, adjust the other A motor PID parameters, of course, the control accuracy is also limited by the motor performance and encoder accuracy, in order to facilitate the PID speed here we rqt_plot graphics curve to the two motor speed, PID input and output display.

3.1. base_controller.py

modify def init(self, arduino, base_frame),Increase the self.debugPID parameter at the beginning, debugPID = true, start debugging, debugPID = false, turn off debugging

class BaseController:
     def __init__(self, arduino, base_frame):
     self.arduino = arduino
     self.base_frame = base_frame
     self.rate = float(rospy.get_param("~base_controller_rate", 10))
     self.timeout = rospy.get_param("~base_controller_timeout", 1.0)
     self.stopped = False
     self.debugPID=False

modify def init(self, arduino, base_frame),Add the following code at the end of the function

if self.debugPID:
     self.lEncoderPub = rospy.Publisher('Lencoder', Int32)
     self.rEncoderPub = rospy.Publisher('Rencoder', Int32)
     self.lPidoutPub = rospy.Publisher('Lpidout', Int32)
     self.rPidoutPub = rospy.Publisher('Rpidout', Int32)
     self.lVelPub = rospy.Publisher('Lvel', Int32)
     self.rVelPub = rospy.Publisher('Rvel', Int32)

modify def poll(self),Add the following code to the function header

if self.debugPID:
     rospy.logdebug("poll start-------------------------------: ")
     try:
         left_pidin, right_pidin = self.arduino.get_pidin()
         self.lEncoderPub.publish(left_pidin)
         self.rEncoderPub.publish(right_pidin)
         rospy.logdebug("left_pidin: "+str(left_pidin))
         rospy.logdebug("right_pidin: "+str(right_pidin))
     except:
         rospy.logerr("getpidin exception count: ")
         return

     try:
         left_pidout, right_pidout = self.arduino.get_pidout()
         self.lPidoutPub.publish(left_pidout)
         self.rPidoutPub.publish(right_pidout)
         rospy.logdebug("left_pidout: "+str(left_pidout))
         rospy.logdebug("right_pidout: "+str(right_pidout))
     except:
         rospy.logerr("getpidout exception count: ")
         return

modify def poll(self),Add the following code after if not self.stopped:

if self.debugPID:
     self.lVelPub.publish(self.v_left)
     self.rVelPub.publish(self.v_right)

3.2. arduino_driver.py

Add get_pidin and get_pidout

def get_pidin(self):
    values = self.execute_array('i')
    if len(values) != 2:
         print "pidin was not 2"
         raise SerialException
         return None
    else:
         return values

def get_pidout(self):
    values = self.execute_array('f')
    if len(values) != 2:
         print "pidout was not 2"
         raise SerialException
         return None
    else:
         return values

3.3. Arduino 的commands.h

and command pidin and pidout

#define READ_PIDOUT    'f'
#define READ_PIDIN     'i'

 

3.4. Arduino 的diff_controller.h

Add readPidIn and readPidOut functions at the end

long readPidIn(int i) {
  long pidin=0;
    if (i == LEFT){
    pidin = leftPID.PrevInput;
  }else {
    pidin = rightPID.PrevInput;
  }
  return pidin;
}

long readPidOut(int i) {
  long pidout=0;
    if (i == LEFT){
    pidout = leftPID.output;
  }else {
    pidout = rightPID.output;
  }
  return pidout;
}

 

3.5. Arduino ROSArduinoBridge.ino

modify runcammand(),Add case READ_PIDIN: and case READ_PIDOUT in the switch section:

  switch (cmd) {
    case GET_BAUDRATE:
      Serial.println(BAUDRATE);
      break;
    case READ_PIDIN:
      Serial.print(readPidIn(LEFT));
      Serial.print(" ");
      Serial.println(readPidIn(RIGHT));
      break;
    case READ_PIDOUT:
      Serial.print(readPidOut(LEFT));
      Serial.print(" ");
      Serial.println(readPidOut(RIGHT));
      break;
     ...

3.6. execute PID speed control

Execute the following commands at different terminals
start roscore

roscore

add path to bash

. ~/catkin_ws/devel/setup.bash

start node

roslaunch ros_arduino_python arduino.launch

At this time we can release the Twist message to control the robot’s operation, such as:

rostopic pub /cmd_vel geometry_msgs/Twist -r 1 -- '[0.5, 0.0, 0.0]' '[0.0, 0.0, 0.0]'

start rqt_plot

rqt_plot

For the use of rqt_plot, see the official documentationhttp://wiki.ros.org/rqt_plot
This time you can rqt_plot provided by the graphical interface, according to the following PID speed formula to debug,

Parameter tuning to find the best, from small to large order check
First after the proportion of points, and finally add the differential plus
Curve oscillation is very frequent, proportional dial to enlarge
Curve floating around the big bay, the proportion of the plate to a small pull
The curve deviates slowly and the integration time goes down
Curve fluctuation cycle is long and the integration time is lengthened
Curve oscillation frequency fast, first differential down
Moving to big slow fluctuations. The derivative time should be longer
Ideal curve of two waves, the former high to low 4 to 1
A look at the two tone more analysis, the quality of regulation will not be low.

Scroll to top