Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: mbed
Lab3.cpp
- Committer:
- JordanWisdom
- Date:
- 2016-02-27
- Revision:
- 7:241bde733699
- Parent:
- 6:1d16cc833e0d
- Child:
- 8:9609a50ea076
File content as of revision 7:241bde733699:
// EE4333 Robotics Lab 3
// Library Imports
//#include "InterruptIn.h"
//#include "rtos.h"
#include "mbed.h"
#include "Serial.h"
#include "stdio.h"
// Function Declarations
void DE0_Init(int);
void L_MotorInit(void);
void R_MotorInit(void);
signed int InputLeft(void);
signed int InputRight(void);
void ControlThread(void);
int SaturateAdd(int x, int y);
float SaturateLimit(float x, float limit);
signed int SignExtend(signed int x);
// ********************************************************************
// GLOBAL VARIABLE DECLARATIONS
// ********************************************************************
signed int R_setpoint; // Desired Angular Speed ( rad/sec )
signed int L_setpoint;
float R_e; // Velocity Error
float R_u; // Control Signal
float L_e;
float L_u;
int L_integrator; // Left Integrator State
int R_integrator;
signed int dPositionLeft; // DE0 Register 0
signed int dPositionRight;
int dTimeLeft; // DE0 Register 1
int dTimeRight;
// *********************************************************************
// PROCESSES AND THREADS
// *********************************************************************
// *********************************************************************
// PIN DECLARATIONS
// *********************************************************************
// Digital I/O Pins
DigitalOut led1(LED1); // Thread Indicators
DigitalOut led2(LED2); //
DigitalOut led3(LED3); //
DigitalOut led4(LED4); //
DigitalOut DirL(p29); // Direction of Left Motor
DigitalOut DirR(p30); // Direction of Right Motor
// SPI Related Digital I/O Pins
DigitalOut SpiReset(p11);
DigitalOut IoReset(p12);
//PWM
PwmOut PwmL(p22);
PwmOut PwmR(p21);
//Serial
Serial pc(USBTX, USBRX); // tx and rx for PC serial channel via USB cable
Serial Bluetooth(p9,p10); // Pins tx(p9) , rx(p10) for bluetooth serial channel
//SPI
SPI DE0(p5,p6,p7); //Pin 5 is MOSI, Pin 6 MISO, Pin 7 SCLK
//Interrupts
Ticker ControlInterrupt; // Internal Interrupt to trigger Control Thread
// ***************************************************
// DE0 Init
// ***************************************************
void DE0_Init(int SpiControlWord){
int mode = 1;
int bits = 16;
DE0.format(bits,mode);
// Verify Peripheral ID
// Generates single square pulse to reset DE0 IO
IoReset = 0;
IoReset = 1;
IoReset = 0;
// Generates single square pulse to reset DE0 SPI
SpiReset = 0;
SpiReset = 1;
SpiReset = 0;
// Writes to DE0 Control Register
int ID = DE0.write(SpiControlWord); // SPI Control Word specifies SPI settings
if(ID == 23){ // DE0 ID 23 (0x0017)
Bluetooth.printf("\n\r >> DE0 Initialized.\n\r");}
else{
Bluetooth.printf("\n\r >> Failed to initialize DE0 board.\n\r");}
}
// ***************************************************
// Left Motor Initialization
// ***************************************************
// Pwm Pin Left Motor : p21
// Direction Pin Left Motor : p29
void L_MotorInit(void){
DirL = 1; // Defaults to 1
// Direction bit logic output
// 0 : Backwards ( Reverse )
// 1 : Forwards ( Advance )
PwmL.period_us(100);
PwmL.write(0);
}
// ***************************************************
// Right Motor Initialization
// ***************************************************
// Pwm Pin Right Motor : p22
// Direction Pin Right Motor : p30
void R_MotorInit(void){
DirR = 0; // Defaults to 0.
// Direction bit logic output
// 0 : Forwards ( Advance )
// 1 : Backwards ( Reverse )
PwmR.period_us(100);
PwmR.write(0);
}
/// ***************************************************
// User Input Left
// ***************************************************
signed int InputLeft(void){
signed int input;
Bluetooth.printf("\n\r Please enter a desired angular speed for the left motor (m/sec) >> ");
Bluetooth.scanf("%i",&input);
Bluetooth.printf("\n\r Your setpoint is >> %i\n\r",input);
return input;
}
/// ***************************************************
// User Input Right
// ***************************************************
signed int InputRight(void){
signed int input;
Bluetooth.printf("\n\r Please enter a desired angular speed for the right motor (m/sec) >> ");
Bluetooth.scanf("%i",&input);
Bluetooth.printf("\n\r Your setpoint is >> %i\n\r",input);
return input;
}
/// ***************************************************
// Control Thread
// ***************************************************
void ControlThread(void){
// Read Incremental Position from DE0 QEI
int dummy = 0x0000; // Pushes dummy information which DE0 ignores, store return from QEI register
dPositionLeft = SignExtend(DE0.write(dummy));
dTimeLeft = DE0.write(dummy);
dPositionRight = SignExtend(DE0.write(dummy));
dTimeRight = DE0.write(dummy);
// Computer Angular Speed and Angular Speed Error
signed int AngularSpeedLeft = (123*dPositionLeft)/dTimeLeft;
signed int AngularSpeedRight = (123*dPositionRight)/dTimeRight;
L_e = L_setpoint - AngularSpeedLeft;
R_e = R_setpoint - AngularSpeedRight;
float Kp_L = 2.5;
float Ki_L = 0.010;
float Kp_R = 2.5;
float Ki_R = 0.010;
if(abs(SaturateLimit((Kp_L*L_e+Ki_L*L_integrator)/35,1))<1){
L_integrator = L_integrator +L_e;}
else{
L_integrator = L_integrator;
}
if(abs(SaturateLimit((Kp_R*R_e+Ki_R*R_integrator)/35,1))<1){
R_integrator = R_integrator +R_e;}
else{
R_integrator = R_integrator;
}
L_u = SaturateLimit( (Kp_L*L_e+Ki_L*L_integrator),1);
R_u = SaturateLimit( (Kp_R*R_e+Ki_R*R_integrator),1);
if(L_u <=0)
DirL = 0;
else
DirL = 1;
if(R_u <=0)
DirR = 1;
else
DirR = 0;
PwmL.write(abs(L_u));
PwmR.write(abs(R_u));
}
/// ***************************************************
// SaturateAdd
// ***************************************************
signed int SaturateAdd(signed int x, signed int y){
signed int z = x + y;
if( (x>0) && (y>0)&& (z<=0) ){
z = 0x7FFFFFFF;}
else if( (x<0)&&(y<0)&&(z>=0) ){
z = 0x80000000;}
return z;
}
/// ***************************************************
// SaturateLimit
// ***************************************************
float SaturateLimit(float x, float limit){
if (x > limit){
return limit;}
else if(x < -limit){
return(-limit);}
else{
return x;}
}
/// ***************************************************
// Sign Extend
// ***************************************************
signed int SignExtend(int x){
if(x&0x00008000){
x = x|0xFFFF0000;
}
return x;
}
// ==============================================================================================================
// ==============================================================================================================
// *********************************************************************
// MAIN FUNCTION
// *********************************************************************
int main(){
// Initialization
DE0_Init(0x8004);
L_MotorInit();
R_MotorInit();
L_integrator = 0;
R_integrator = 0;
ControlInterrupt.attach(&ControlThread, 0.0005);
// Specify Setpoint ( rads/sec )
L_setpoint = InputLeft()/0.05093; //The 0.05093 converts from a m/s input to a rad/s control calculation
R_setpoint = InputRight()/0.05093; //The 0.05093 converts from a m/s input to a rad/s control calculation
// Display Global Variables to Console
Bluetooth.printf("\n\r ========= LEFT ======= ========= RIGHT =======");
Bluetooth.printf("\n\r US VE IS CS US VE IS CS ");
while(1){
float L_error_t = L_e;
float L_u_t = L_u;
float R_error_t = R_e;
float R_u_t = R_u;
float L_setpoint_m = L_setpoint*0.05093; //Setpoints in meters per second float values for display
float R_setpoint_m = L_setpoint*0.05093; //Setpoints in meters per second float values for display
Bluetooth.printf("\n\r %2.2f %2.1f %i %2.2f %2.2f %2.1f %i %2.2f",L_setpoint_m,L_error_t*0.05093,L_integrator,L_u_t,R_setpoint_m,R_error_t*0.05093,R_integrator,R_u_t);
wait(0.75);
}
}