PID motor controll for the biorobotics project.

Dependencies:   FastPWM QEI

Dependents:   PID_example Motor_calibration Demo_mode Demo_mode ... more

Committer:
brass_phoenix
Date:
Wed Oct 31 08:01:35 2018 +0000
Revision:
6:d83c79716ea1
Parent:
5:5537072b0e2e
Child:
7:eb8787e7a5f5
* Stop now sets the target angle to the current angle.

Who changed what in which revision?

UserRevisionLine numberNew contents of line
brass_phoenix 0:009e84d7af32 1 #include "motor.h"
brass_phoenix 0:009e84d7af32 2
brass_phoenix 2:b30a467e90d3 3 Motor::Motor(PinName pwm_pin, PinName dir_pin, PinName encoder_a, PinName encoder_b):
brass_phoenix 2:b30a467e90d3 4 pwm_out(pwm_pin),
brass_phoenix 2:b30a467e90d3 5 dir_out(dir_pin),
brass_phoenix 2:b30a467e90d3 6 encoder(encoder_a, encoder_b, NC, PULSES_PER_ROTATION, QEI::X4_ENCODING)
brass_phoenix 2:b30a467e90d3 7 {
brass_phoenix 2:b30a467e90d3 8 pid = PID();
brass_phoenix 2:b30a467e90d3 9
brass_phoenix 2:b30a467e90d3 10 target_angle = 0;
brass_phoenix 2:b30a467e90d3 11
brass_phoenix 2:b30a467e90d3 12 printcount = 0;
brass_phoenix 2:b30a467e90d3 13 pid_period = 0;
brass_phoenix 2:b30a467e90d3 14 serial_debugging = false;
brass_phoenix 2:b30a467e90d3 15
brass_phoenix 2:b30a467e90d3 16 // 60 microseconds PWM period, 16.7 kHz, defines all PWM pins (only needs to be done once)
brass_phoenix 2:b30a467e90d3 17 pwm_out.period_us(60.0);
brass_phoenix 2:b30a467e90d3 18 }
brass_phoenix 2:b30a467e90d3 19
brass_phoenix 0:009e84d7af32 20 Motor::Motor(PinName pwm_pin, PinName dir_pin, PinName encoder_a, PinName encoder_b, Serial* pc):
brass_phoenix 0:009e84d7af32 21 pwm_out(pwm_pin),
brass_phoenix 0:009e84d7af32 22 dir_out(dir_pin),
brass_phoenix 0:009e84d7af32 23 encoder(encoder_a, encoder_b, NC, PULSES_PER_ROTATION, QEI::X4_ENCODING)
brass_phoenix 0:009e84d7af32 24 {
brass_phoenix 0:009e84d7af32 25 pid = PID();
brass_phoenix 0:009e84d7af32 26
brass_phoenix 0:009e84d7af32 27 target_angle = 0;
brass_phoenix 0:009e84d7af32 28
brass_phoenix 0:009e84d7af32 29 printcount = 0;
brass_phoenix 0:009e84d7af32 30 pid_period = 0;
brass_phoenix 0:009e84d7af32 31 this->pc = pc;
brass_phoenix 2:b30a467e90d3 32 serial_debugging = true;
brass_phoenix 0:009e84d7af32 33
brass_phoenix 0:009e84d7af32 34 // 60 microseconds PWM period, 16.7 kHz, defines all PWM pins (only needs to be done once)
brass_phoenix 0:009e84d7af32 35 pwm_out.period_us(60.0);
brass_phoenix 0:009e84d7af32 36 }
brass_phoenix 0:009e84d7af32 37
brass_phoenix 0:009e84d7af32 38 void Motor::start(float period) {
brass_phoenix 0:009e84d7af32 39 pid_period = period;
brass_phoenix 0:009e84d7af32 40 pid.set_period(period);
brass_phoenix 4:5353c5d0d2ed 41 motor_ticker.attach(callback(this, &Motor::update), period);
brass_phoenix 4:5353c5d0d2ed 42 }
brass_phoenix 4:5353c5d0d2ed 43
brass_phoenix 4:5353c5d0d2ed 44 void Motor::stop() {
brass_phoenix 4:5353c5d0d2ed 45 motor_ticker.detach();
brass_phoenix 6:d83c79716ea1 46 target_angle = get_current_angle();
brass_phoenix 4:5353c5d0d2ed 47 // Stop the actual motor.
brass_phoenix 4:5353c5d0d2ed 48 pwm_out = 0.0;
brass_phoenix 4:5353c5d0d2ed 49 dir_out = 0;
brass_phoenix 4:5353c5d0d2ed 50
brass_phoenix 4:5353c5d0d2ed 51 pid.clear_state();
brass_phoenix 4:5353c5d0d2ed 52
brass_phoenix 4:5353c5d0d2ed 53 printcount = 0;
brass_phoenix 0:009e84d7af32 54 }
brass_phoenix 0:009e84d7af32 55
brass_phoenix 5:5537072b0e2e 56 void Motor::set_current_angle_as_zero() {
brass_phoenix 5:5537072b0e2e 57 encoder.reset();
brass_phoenix 5:5537072b0e2e 58 target_angle = 0;
brass_phoenix 5:5537072b0e2e 59 }
brass_phoenix 5:5537072b0e2e 60
brass_phoenix 0:009e84d7af32 61 void Motor::set_pid_k_values(double k_p, double k_i, double k_d) {
brass_phoenix 0:009e84d7af32 62 pid.set_k_values(k_p, k_i, k_d);
brass_phoenix 0:009e84d7af32 63 }
brass_phoenix 0:009e84d7af32 64
brass_phoenix 0:009e84d7af32 65 void Motor::set_target_angle(double angle) {
brass_phoenix 0:009e84d7af32 66 target_angle = angle;
brass_phoenix 0:009e84d7af32 67 }
brass_phoenix 0:009e84d7af32 68
brass_phoenix 0:009e84d7af32 69 double Motor::get_current_angle() {
brass_phoenix 0:009e84d7af32 70 return encoder_pulses_to_radians(encoder.getPulses());
brass_phoenix 0:009e84d7af32 71 }
brass_phoenix 0:009e84d7af32 72
brass_phoenix 0:009e84d7af32 73 void Motor::update() {
brass_phoenix 0:009e84d7af32 74 int pulses = encoder.getPulses();
brass_phoenix 0:009e84d7af32 75 double current_angle = encoder_pulses_to_radians(pulses);
brass_phoenix 0:009e84d7af32 76
brass_phoenix 0:009e84d7af32 77 double error = current_angle - target_angle;
brass_phoenix 0:009e84d7af32 78 // PID controll.
brass_phoenix 0:009e84d7af32 79 double speed_rps = pid.update(error);
brass_phoenix 0:009e84d7af32 80
brass_phoenix 0:009e84d7af32 81 double speed_pwm = radians_per_second_to_pwm(speed_rps);
brass_phoenix 0:009e84d7af32 82
brass_phoenix 2:b30a467e90d3 83 if (serial_debugging) {
brass_phoenix 2:b30a467e90d3 84
brass_phoenix 2:b30a467e90d3 85 printcount++;
brass_phoenix 2:b30a467e90d3 86 if (printcount >= 0.1L/pid_period) {
brass_phoenix 2:b30a467e90d3 87 pc->printf("c_angle: %f, d_angle: %f, error: %f, rps: %f, speed: %f\n", current_angle, target_angle, error, speed_rps, speed_pwm);
brass_phoenix 2:b30a467e90d3 88 printcount = 0;
brass_phoenix 2:b30a467e90d3 89 }
brass_phoenix 0:009e84d7af32 90 }
brass_phoenix 0:009e84d7af32 91
brass_phoenix 0:009e84d7af32 92 update_motor_speed(speed_pwm);
brass_phoenix 0:009e84d7af32 93 }
brass_phoenix 0:009e84d7af32 94
brass_phoenix 0:009e84d7af32 95
brass_phoenix 0:009e84d7af32 96 void Motor::update_motor_speed(double speed) {
brass_phoenix 0:009e84d7af32 97 if (speed < 1.0 && speed > 0) {
brass_phoenix 0:009e84d7af32 98 // Speed is in the range [0, 1] but the motor only moves
brass_phoenix 0:009e84d7af32 99 // in the range [0.5, 1]. Rescale for this.
brass_phoenix 0:009e84d7af32 100 speed = (speed * (1-MOTOR_STALL_PWM)) + MOTOR_STALL_PWM;
brass_phoenix 0:009e84d7af32 101 }
brass_phoenix 0:009e84d7af32 102 if (speed > -1.0 && speed < 0) {
brass_phoenix 0:009e84d7af32 103 // Speed is in the range [-1, 0] but the motor only moves
brass_phoenix 0:009e84d7af32 104 // in the range [-1, -0.5]. Rescale for this.
brass_phoenix 0:009e84d7af32 105 speed = (speed * (1-MOTOR_STALL_PWM)) - MOTOR_STALL_PWM;
brass_phoenix 0:009e84d7af32 106 }
brass_phoenix 0:009e84d7af32 107
brass_phoenix 0:009e84d7af32 108 // either true or false, determines direction (0 or 1)
brass_phoenix 0:009e84d7af32 109 dir_out = speed > 0;
brass_phoenix 0:009e84d7af32 110 // pwm duty cycle can only be positive, floating point absolute value (if value is >0, the there still will be a positive value).
brass_phoenix 0:009e84d7af32 111 pwm_out = fabs(speed);
brass_phoenix 0:009e84d7af32 112 }
brass_phoenix 0:009e84d7af32 113
brass_phoenix 0:009e84d7af32 114 double Motor::encoder_pulses_to_radians(int pulses) {
brass_phoenix 0:009e84d7af32 115 return (pulses/float(PULSES_PER_ROTATION)) * 2.0f*PI;
brass_phoenix 0:009e84d7af32 116 }
brass_phoenix 0:009e84d7af32 117
brass_phoenix 0:009e84d7af32 118
brass_phoenix 0:009e84d7af32 119 // Converts radians/s values into PWM values for motor controll.
brass_phoenix 0:009e84d7af32 120 // Both positive and negative values.
brass_phoenix 0:009e84d7af32 121 double Motor::radians_per_second_to_pwm(double rps) {
brass_phoenix 0:009e84d7af32 122 // If the rad/s is below the anti-jitter treshold, it is simply 0.
brass_phoenix 0:009e84d7af32 123 if (rps > 0 && rps < MOTOR_THRESHOLD_RPS) {
brass_phoenix 0:009e84d7af32 124 rps = 0;
brass_phoenix 0:009e84d7af32 125 }
brass_phoenix 0:009e84d7af32 126 if (rps < 0 && rps > -MOTOR_THRESHOLD_RPS) {
brass_phoenix 0:009e84d7af32 127 rps = 0;
brass_phoenix 0:009e84d7af32 128 }
brass_phoenix 0:009e84d7af32 129
brass_phoenix 0:009e84d7af32 130
brass_phoenix 0:009e84d7af32 131 // With our specific motor, full PWM is equal to 1 round per second.
brass_phoenix 0:009e84d7af32 132 // Or 2PI radians per second.
brass_phoenix 0:009e84d7af32 133 double pwm_speed = rps / (2*PI);
brass_phoenix 0:009e84d7af32 134
brass_phoenix 0:009e84d7af32 135 // PWM speeds can only go between [-1, 1]
brass_phoenix 0:009e84d7af32 136 if (pwm_speed > 1) { pwm_speed = 1; }
brass_phoenix 0:009e84d7af32 137 if (pwm_speed < -1) { pwm_speed = -1; }
brass_phoenix 0:009e84d7af32 138 return pwm_speed;
brass_phoenix 0:009e84d7af32 139 }