Hardware components | ||||||
![]() |
| × | 1 | |||
| × | 2 | ||||
| × | 2 | ||||
Software apps and online services | ||||||
![]() |
| |||||
![]() |
| |||||
Hand tools and fabrication machines | ||||||
![]() |
|
This project goal was to use servos and swing up control to catapult a marble over the wood box in the lab room.
Background: In order to add energy to the ball throwing motion, we want the robot to swing up from its car state (lab 6 PD controller) to its Segbot state (lab 7 PD controller). This will entail running the motors fast to go forward and then suddenly reversing direction to force a sharp change in momentum which will cause the robot to 'swing up' from its car position. In order to achieve this, weight will need to be adjusted properly along the car to ensure the momentum change and motor torque is sufficient to swing up the car.
Implementation: First, we tried implemented swing-up with the default car to see if it was feasible. Using the distance sensor, we can determine how close the car gets to the wall before it changes from full throttle to segbot control. We also adjusted the balance point offset so that we can calibrate the car when it is in its normal, horizontal position. Due to this, the segbot control sends full reverse signal to the motors by default when the car is horizontal, so we switch between control algorithms to initiate swing-up, instead of adding an extra amount of hard-coded reverse signal. This turned out to work well, and the robot balanced very well after the swing up motion.
Next, we designed and 3D-Printed a new base plate and the catapult. With these parts, we rebuilt the car to which allows us to move the battery mounting position towards the 2 motors. We also taped an additional dead battery on the front for extra weight. With this, the weight of the catapult was sufficiently offset, and we were able to get swing-up to work again. Notably, the balancing would sometimes not find the steady state after swing up, and the car needed an extra nudge to right itself, or it would drift off into a wall.
Additionally, we added LED indications for each 'mode' the robot is in, useful for debugging and adjusting timings. Each row of the LEDs lights up to signify a different state - Manual (free to steer with LabView), Charge (full throttle into a wall), or Segbot mode.
Part 2: Servo ControlBackground: The motion of the robot car swinging upwards will not be enough to properly launch the projectile. Instead, a catapult will be activated simultaneously alongside the swing up control to achieve greater distance and efficacy.
Implementation: Using the EPWM2A and B duty cycle, we can control the servos to specific angles at any time. From trail and error, we found specific angles to toggle between for both servos.=
As seen in Figure 1, the two servo motors lock/release the lever arm (Servo 1) and tighten/release tension (Servo 2) in the catapult. In its loaded state, the catapult has the Servo 1 locked and Servo 2 tightened.
By rotating the latch attached to Servo 1, the lever arm is free to rotate, propelled forward by the rubber band attached to Servo 2. Once the catapult has released its projectile, extra tension in the spring can be relieved by rotating Servo 2 by 180 degrees. This motion then allows the lever arm to fall back downwards; once it is in its neutral position, Servo 1 can rotate and lock it in place, and Servo 2 can then reapply tension into the lever arm. The catapult will then be ready to be loaded and fired again, like the state seen in Figure 2.
Lastly, we integrate both of the aforementioned steps. Using LabVIEW to control the car, we can steer around in Manual mode, enable Charge Mode, which automatically enters Segbot Mode once the distance sensor sees a wall. The catapult latch servo is released after a set time, to launch the projectile with the car's swing-up motion. Then, we can disable Segbot Mode and steer around normally again, ready to reload the catapult and launch another projectile.
Working Demonstration//#############################################################################
// FILE: LAB6starter_main.c
//
// TITLE: Lab Starter
//#############################################################################
// Included Files
#include <stdio.h>
#include <stdlib.h>
#include <stdarg.h>
#include <string.h>
#include <math.h>
#include <limits.h>
#include "F28x_Project.h"
#include "driverlib.h"
#include "device.h"
#include "F28379dSerial.h"
#include "LEDPatterns.h"
#include "song.h"
#include "dsp.h"
#include "fpu32/fpu_rfft.h"
#define PI 3.1415926535897932384626433832795
#define TWOPI 6.283185307179586476925286766559
#define HALFPI 1.5707963267948966192313216916398
// The Launchpad's CPU Frequency set to 200 you should not change this value
#define LAUNCHPAD_CPU_FREQUENCY 200
// ----- code for CAN start here -----
#include "F28379dCAN.h"
//#define TX_MSG_DATA_LENGTH 4
//#define TX_MSG_OBJ_ID 0 //transmit
#define RX_MSG_DATA_LENGTH 8
#define RX_MSG_OBJ_ID_1 1 //measurement from sensor 1
#define RX_MSG_OBJ_ID_2 2 //measurement from sensor 2
#define RX_MSG_OBJ_ID_3 3 //quality from sensor 1
#define RX_MSG_OBJ_ID_4 4 //quality from sensor 2
// ----- code for CAN end here -----
// Interrupt Service Routines predefinition
__interrupt void cpu_timer0_isr(void);
__interrupt void cpu_timer1_isr(void);
__interrupt void cpu_timer2_isr(void);
__interrupt void ADCA_ISR (void);
__interrupt void SWI_isr(void);
// ----- code for CAN start here -----
__interrupt void can_isr(void);
// ----- code for CAN end here -----
__interrupt void SPIB_isr(void);
void setupSpib(void);
void init_eQEPs(void);
float readEncLeft(void);
float readEncRight(void);
void setEPWM2A(float);
void setEPWM2B(float);
// Lab7 Exercise 1
int32_t adca1_interrupt_count = 0;
int16_t adca2result = 0;
int16_t adca3result = 0;
float joystick_X = 0;
float joystick_Y = 0;
// Count variables
uint32_t numTimer0calls = 0;
uint32_t numSWIcalls = 0;
extern uint32_t numRXA;
uint16_t UARTPrint = 0;
uint16_t LEDdisplaynum = 0;
int16_t accelx_raw = 0;
int16_t accely_raw = 0;
int16_t accelz_raw = 0;
int16_t gyrox_raw = 0;
int16_t gyroy_raw = 0;
int16_t gyroz_raw = 0;
float accelx = 0;
float accely = 0;
float accelz = 0;
float gyrox = 0;
float gyroy = 0;
float gyroz = 0;
// JK/LB Variables for Distance and Velocity calculations
float LeftWheelRadians = 0;
float RightWheelRadians = 0;
float LeftWheelDist_K = 0; // [meters]
float RightWheelDist_K = 0; // [meters]
float uLeft = 0; // Control effort variables for EPWM2A,B
float uRight = 0;
float RightWheelDist_K_1 = 0;
float LeftWheelDist_K_1 = 0;
float RightWheelVel = 0;
float LeftWheelVel = 0;
// JK LB - variables for the PI controller
float Vref = 0; // m/s
float Kp = 3;
float Ki = 25;
float I_Right_K = 0;
float e_Right_K = 0;
float I_Right_K_1 = 0;
float e_Right_K_1 = 0;
float I_Left_K = 0;
float e_Left_K = 0;
float I_Left_K_1 = 0;
float e_Left_K_1 = 0;
float Kturn = 3;
float e_turn = 0;
float turn = 0;
// LB - Variables for Exercise 5 - Wireless Control with LabVIEW
float printLV3 = 0;
float printLV4 = 0;
float printLV5 = 0;
float printLV6 = 0;
float printLV7 = 0;
float printLV8 = 0;
float x = 0;
float y = 0;
float bearing = 0;// Robot Pose Angle a.k.a. Bearing [rad]
extern uint16_t NewLVData;
extern float fromLVvalues[LVNUM_TOFROM_FLOATS];
extern LVSendFloats_t DataToLabView;
extern char LVsenddata[LVNUM_TOFROM_FLOATS*4+2];
extern uint16_t newLinuxCommands;
extern float LinuxCommands[CMDNUM_FROM_FLOATS];
// LB - Variables for Exercise 6 - Pose Calculation
float W_r = 0.185; // Robot Width (width between wheels) [meters]
float R_wh = 0.0593; // Wheel Radius [meters]
float theta_L_K = 0; // current left wheel rotation angle [rad]
float theta_R_K = 0; // current right wheel rotation angle [rad]
float theta_L_K_1 = 0; // previous left wheel rotation angle [rad]
float theta_R_K_1 = 0; // previous right wheel rotation angle [rad]
float theta_avg = 0; // [rad]
float theta_dot_avg = 0; // [rad/s]
float theta_dot_R = 0;
float theta_dot_L = 0;
float x_dot_K = 0; // [m/s]
float y_dot_K = 0; // [m/s]'
float x_dot_K_1 = 0;
float y_dot_K_1 = 0;
float x_K_1 = 0;
float y_K_1 = 0;
// Variables for Exercise 7 - Wall Following
uint32_t distright = 0;
uint32_t distfront = 0;
float Kpright = 0.001;
float Kpfront = 0.0002;
uint32_t ref_right = 200;
uint32_t ref_front = 1400;
uint16_t rightwallfollow = 1;
uint32_t threshold_1 = 500;
uint32_t threshold_2 = 500;
// Lab 7 Exercise 2 - Needed global Variables
float accelx_offset = 0;
float accely_offset = 0;
float accelz_offset = 0;
float gyrox_offset = 0;
float gyroy_offset = 0;
float gyroz_offset = 0;
// float accelzBalancePoint = 0.315; // for batteries on the uprights
float accelzBalancePoint = 0.71; // for when no batteries on uprights
int16 IMU_data[9];
uint16_t temp=0;
int16_t doneCal = 0;
float tilt_value = 0;
float tilt_array[4] = {0, 0, 0, 0};
float gyro_value = 0;
float gyro_array[4] = {0, 0, 0, 0};
float LeftWheel = 0;
float RightWheel = 0;
float LeftWheelArray[4] = {0,0,0,0};
float RightWheelArray[4] = {0,0,0,0};
// Kalman Filter vars
float T = 0.001; //sample rate, 1ms
float Q = 0.01; // made global to enable changing in runtime
float R = 25000;//50000;
float kalman_tilt = 0;
float kalman_P = 22.365;
int16_t SpibNumCalls = -1;
float pred_P = 0;
float kalman_K = 0;
int32_t timecount = 0;
int16_t calibration_state = 0;
int32_t calibration_count = 0;
// Exercise 3 variables
float theta_K_1 = 0;
float theta_dot_K_1 = 0;
float vel_Right = 0;
float vel_Left = 0;
float RightWheel_dot = 0;
float RightWheel_K_1 = 0;
float RightWheel_dot_K_1 = 0;
float LeftWheel_dot = 0;
float LeftWheel_K_1 = 0;
float LeftWheel_dot_K_1 = 0;
float gyrorate_dot = 0;
float gyro_value_K_1 = 0;
float gyrorate_dot_K_1 = 0;
// Exercise 2+3 variables for balancing
float K1 = -60;
float K2 = -4.5;
float K3 = -1.1;
float K4 = -0.1;
float ubal = 0;
// Exercise 4 variables for turning
float WhlDiff = 0.0;
float WhelDiff_1 = 0.0;
float vel_WhlDiff = 0.0;
float vel_WhlDiff_1 = 0.0;
float turnref = 0.0;
float errorDiff = 0.0;
float errorDiff_1 = 0.0;
float intDiff = 0.0;
float intDiff_1 = 0.0;
float WhlDiff_1 = 0.0;
float Kp_turn = 3.0;
float Ki_turn = 20.0;
float Kd_turn = 0.08;
float turnrate = 0.0;
float turnrate_1 = 0.0;
float turnref_1 = 0.0;
//EXERCISE 5: defining variables for speed control
float ForwardBackwardCommand = 0.0;
float eSpeed = 0.0;
float eSpeed_1 = 0.0;
float Segbot_refSpeed = 0.0;
float Segbot_refSpeed_1 = 0.0;
float KpSpeed = 0.35;
float KiSpeed = 1.5;
//float KiSpeed = 0;
float IK_eSpeed = 0.0;
float IK_eSpeed_1 = 0.0;
// FINAL PROJECT variables
uint16_t segbotMode = 0;
uint16_t manualMode = 1;
uint16_t chargeMode = 0;
float segbot_Threshold = 450.0;
uint16_t readyToGo = 0;
float uRight_normal = 0;
float uLeft_normal = 0;
float turn_normal = 0;
float latched_angle = 0;
float unlatched_angle = -90;
float relaxed_rubberband_angle = 90;
float stretched_rubberband_angle = -90;
uint16_t launchCounter = 0;
uint16_t segbotCounter = 0;
uint16_t segbot_Offset = 0;
// ----- code for CAN start here -----
// volatile uint32_t txMsgCount = 0;
// extern uint16_t txMsgData[4];
volatile uint32_t rxMsgCount_1 = 0;
volatile uint32_t rxMsgCount_3 = 0;
extern uint16_t rxMsgData[8];
uint32_t dis_raw_1[2];
uint32_t dis_raw_3[2];
uint32_t dis_1 = 0;
uint32_t dis_3 = 0;
uint32_t quality_raw_1[4];
uint32_t quality_raw_3[4];
float quality_1 = 0.0;
float quality_3 = 0.0;
uint32_t lightlevel_raw_1[4];
uint32_t lightlevel_raw_3[4];
float lightlevel_1 = 0.0;
float lightlevel_3 = 0.0;
uint32_t measure_status_1 = 0;
uint32_t measure_status_3 = 0;
volatile uint32_t errorFlag = 0;
// ----- code for CAN end here -----
//LB&JT - CopyPasted code for initializing and reading motor angle, using quadrature optical encoder
void init_eQEPs(void) {
// setup eQEP1 pins for input
EALLOW;
//Disable internal pull-up for the selected output pins for reduced power consumption
GpioCtrlRegs.GPAPUD.bit.GPIO20 = 1; // Disable pull-up on GPIO20 (EQEP1A)
GpioCtrlRegs.GPAPUD.bit.GPIO21 = 1; // Disable pull-up on GPIO21 (EQEP1B)
GpioCtrlRegs.GPAQSEL2.bit.GPIO20 = 2; // Qual every 6 samples
GpioCtrlRegs.GPAQSEL2.bit.GPIO21 = 2; // Qual every 6 samples
EDIS;
// This specifies which of the possible GPIO pins will be EQEP1 functional pins.
// Comment out other unwanted lines.
GPIO_SetupPinMux(20, GPIO_MUX_CPU1, 1);
GPIO_SetupPinMux(21, GPIO_MUX_CPU1, 1);
EQep1Regs.QEPCTL.bit.QPEN = 0; // make sure eqep in reset
EQep1Regs.QDECCTL.bit.QSRC = 0; // Quadrature count mode
EQep1Regs.QPOSCTL.all = 0x0; // Disable eQep Position Compare
EQep1Regs.QCAPCTL.all = 0x0; // Disable eQep Capture
EQep1Regs.QEINT.all = 0x0; // Disable all eQep interrupts
EQep1Regs.QPOSMAX = 0xFFFFFFFF; // use full range of the 32 bit count
EQep1Regs.QEPCTL.bit.FREE_SOFT = 2; // EQep uneffected by emulation suspend in Code Composer
EQep1Regs.QPOSCNT = 0;
EQep1Regs.QEPCTL.bit.QPEN = 1; // Enable EQep
// setup QEP2 pins for input
EALLOW;
//Disable internal pull-up for the selected output pinsfor reduced power consumption
GpioCtrlRegs.GPBPUD.bit.GPIO54 = 1; // Disable pull-up on GPIO54 (EQEP2A)
GpioCtrlRegs.GPBPUD.bit.GPIO55 = 1; // Disable pull-up on GPIO55 (EQEP2B)
GpioCtrlRegs.GPBQSEL2.bit.GPIO54 = 2; // Qual every 6 samples
GpioCtrlRegs.GPBQSEL2.bit.GPIO55 = 2; // Qual every 6 samples
EDIS;
GPIO_SetupPinMux(54, GPIO_MUX_CPU1, 5); // set GPIO54 and eQep2A
GPIO_SetupPinMux(55, GPIO_MUX_CPU1, 5); // set GPIO54 and eQep2B
EQep2Regs.QEPCTL.bit.QPEN = 0; // make sure qep reset
EQep2Regs.QDECCTL.bit.QSRC = 0; // Quadrature count mode
EQep2Regs.QPOSCTL.all = 0x0; // Disable eQep Position Compare
EQep2Regs.QCAPCTL.all = 0x0; // Disable eQep Capture
EQep2Regs.QEINT.all = 0x0; // Disable all eQep interrupts
EQep2Regs.QPOSMAX = 0xFFFFFFFF; // use full range of the 32 bit count.
EQep2Regs.QEPCTL.bit.FREE_SOFT = 2; // EQep uneffected by emulation suspend
EQep2Regs.QPOSCNT = 0;
EQep2Regs.QEPCTL.bit.QPEN = 1; // Enable EQep
}
float readEncLeft(void) {
int32_t raw = 0;
uint32_t QEP_maxvalue = 0xFFFFFFFFU; //4294967295U
raw = EQep1Regs.QPOSCNT;
if (raw >= QEP_maxvalue/2) raw -= QEP_maxvalue; // I don't think this is needed and never true
// 100 slits in the encoder disk so 100 square waves per one revolution of the
// DC motor's back shaft. Then Quadrature Decoder mode multiplies this by 4 so 400 counts per one rev
// of the DC motor's back shaft. Then the gear motor's gear ratio is 30:1.
return (-raw*(TWOPI)/(400*30)); // Return angle of wheel, in RADIANS. (ticks) * 1 wheel revolution per 12000 ticks * 2pi rad per revolution
}
float readEncRight(void) {
int32_t raw = 0;
uint32_t QEP_maxvalue = 0xFFFFFFFFU; //4294967295U -1 32bit signed int
raw = EQep2Regs.QPOSCNT;
if (raw >= QEP_maxvalue/2) raw -= QEP_maxvalue; // I don't think this is needed and never true
// 100 slits in the encoder disk so 100 square waves per one revolution of the
// DC motor's back shaft. Then Quadrature Decoder mode multiplies this by 4 so 400 counts per one rev
// of the DC motor's back shaft. Then the gear motor's gear ratio is 30:1.
return (raw*(TWOPI)/(400*30));
}
// LB*JT - CopyPasted code from Lab 3 for setting motor speeds via EPWM2
void setEPWM2A(float controleffort) {
if (controleffort > 10) //LB - saturate controleffort to be within (-10, 10)
controleffort = 10;
if (controleffort < -10)
controleffort = -10;
float scaled_effort = 1250 + (controleffort*125); // LB - scale controleffort such that 10 equates to 2500 and -10 equates to 0
EPwm2Regs.CMPA.bit.CMPA = scaled_effort;
}
void setEPWM2B(float controleffort) {
if (controleffort > 10) //LB - saturate controleffort to be within (-10, 10)
controleffort = 10;
if (controleffort < -10)
controleffort = -10;
float scaled_effort = 1250 + (controleffort*125); // LB - scale controleffort such that 10 equates to 2500 and -10 equates to 0
EPwm2Regs.CMPB.bit.CMPB = scaled_effort;
}
// CopyPasted from Lab 3 - RC Servo Control
void setEPWM8A_RCServo(float angle) {
if (angle > 90) //LB - saturate anlge to be within (-90, 90)
angle = 90;
if (angle < -90)
angle = -90;
float scaled_angle = 0.08 + angle*0.04/90; // LB&JT - convert angle to duty cycle
EPwm8Regs.CMPA.bit.CMPA = scaled_angle * 62500; // LB&JT - set CMPA to % duty cycle based on angle
}
void setEPWM8B_RCServo(float angle) {
if (angle > 90) //LB - saturate anlge to be within (-90, 90)
angle = 90;
if (angle < -90)
angle = -90;
float scaled_angle = 0.08 + angle*0.04/90; // LB&JT - convert angle to duty cycle
EPwm8Regs.CMPB.bit.CMPB = scaled_angle * 62500; // LB&JT - set CMPA to % duty cycle based on angle
}
void SetLEDRowsOnOff(int16_t rows) { // used for viewing different modes
if ((rows & 0x1) == 0x1) {
//LB&JT- check if bit 0 is 1, turn on first row
GpioDataRegs.GPASET.bit.GPIO22 = 1;
GpioDataRegs.GPESET.bit.GPIO130 = 1;
GpioDataRegs.GPBSET.bit.GPIO60 = 1;
} else {
//LB - turn off row 1
GpioDataRegs.GPACLEAR.bit.GPIO22 = 1;
GpioDataRegs.GPECLEAR.bit.GPIO130 = 1;
GpioDataRegs.GPBCLEAR.bit.GPIO60 = 1;
}
if ((rows & 0x2) == 0x2) {
//LB&JT- check if bit 1 bit is 1, turn on second row
GpioDataRegs.GPCSET.bit.GPIO94 = 1;
GpioDataRegs.GPESET.bit.GPIO131 = 1;
GpioDataRegs.GPBSET.bit.GPIO61 = 1;
} else {
//LB - turn off row 2
GpioDataRegs.GPCCLEAR.bit.GPIO94 = 1;
GpioDataRegs.GPECLEAR.bit.GPIO131 = 1;
GpioDataRegs.GPBCLEAR.bit.GPIO61 = 1;
}
if ((rows & 0x4) == 0x4) {
//LB&JT- check if bit 2 is 1, turn on third row
GpioDataRegs.GPCSET.bit.GPIO95 = 1;
GpioDataRegs.GPASET.bit.GPIO25 = 1;
GpioDataRegs.GPESET.bit.GPIO157 = 1;
} else {
//LB - turn off row 3
GpioDataRegs.GPCCLEAR.bit.GPIO95 = 1;
GpioDataRegs.GPACLEAR.bit.GPIO25 = 1;
GpioDataRegs.GPECLEAR.bit.GPIO157 = 1;
}
if ((rows & 0x8) == 0x8) {
//LB&JT- check if bit 3 is 1, turn on fourth row
GpioDataRegs.GPDSET.bit.GPIO97 = 1;
GpioDataRegs.GPASET.bit.GPIO26 = 1;
GpioDataRegs.GPESET.bit.GPIO158 = 1;
} else {
//LB - turn off row 4
GpioDataRegs.GPDCLEAR.bit.GPIO97 = 1;
GpioDataRegs.GPACLEAR.bit.GPIO26 = 1;
GpioDataRegs.GPECLEAR.bit.GPIO158 = 1;
}
if ((rows & 0x10) == 0x10) {
//LB&JT- check if bit 4 is 1, turn on fifth row
GpioDataRegs.GPDSET.bit.GPIO111 = 1;
GpioDataRegs.GPASET.bit.GPIO27 = 1;
GpioDataRegs.GPESET.bit.GPIO159 = 1;
} else {
//LB - turn off row 5
GpioDataRegs.GPDCLEAR.bit.GPIO111 = 1;
GpioDataRegs.GPACLEAR.bit.GPIO27 = 1;
GpioDataRegs.GPECLEAR.bit.GPIO159 = 1;
}
}
void main(void) {
// PLL, WatchDog, enable Peripheral Clocks
// This example function is found in the F2837xD_SysCtrl.c file.
InitSysCtrl();
InitGpio();
// Blue LED on LaunchPad
GPIO_SetupPinMux(31, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(31, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO31 = 1;
// Red LED on LaunchPad
GPIO_SetupPinMux(34, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(34, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPBSET.bit.GPIO34 = 1;
// LED1 and PWM Pin
GPIO_SetupPinMux(22, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(22, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPACLEAR.bit.GPIO22 = 1;
// LED2
GPIO_SetupPinMux(94, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(94, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPCCLEAR.bit.GPIO94 = 1;
// LED3
GPIO_SetupPinMux(95, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(95, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPCCLEAR.bit.GPIO95 = 1;
// LED4
GPIO_SetupPinMux(97, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(97, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPDCLEAR.bit.GPIO97 = 1;
// LED5
GPIO_SetupPinMux(111, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(111, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPDCLEAR.bit.GPIO111 = 1;
// LED6
GPIO_SetupPinMux(130, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(130, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPECLEAR.bit.GPIO130 = 1;
// LED7
GPIO_SetupPinMux(131, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(131, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPECLEAR.bit.GPIO131 = 1;
// LED8
GPIO_SetupPinMux(25, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(25, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPACLEAR.bit.GPIO25 = 1;
// LED9
GPIO_SetupPinMux(26, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(26, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPACLEAR.bit.GPIO26 = 1;
// LED10
GPIO_SetupPinMux(27, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(27, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPACLEAR.bit.GPIO27 = 1;
// LED11
GPIO_SetupPinMux(60, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(60, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPBCLEAR.bit.GPIO60 = 1;
// LED12
GPIO_SetupPinMux(61, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(61, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPBCLEAR.bit.GPIO61 = 1;
// LED13
GPIO_SetupPinMux(157, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(157, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPECLEAR.bit.GPIO157 = 1;
// LED14
GPIO_SetupPinMux(158, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(158, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPECLEAR.bit.GPIO158 = 1;
// LED15
GPIO_SetupPinMux(159, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(159, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPECLEAR.bit.GPIO159 = 1;
// LED16
GPIO_SetupPinMux(160, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(160, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPFCLEAR.bit.GPIO160 = 1;
//WIZNET Reset
GPIO_SetupPinMux(0, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(0, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO0 = 1;
//ESP8266 Reset
GPIO_SetupPinMux(1, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(1, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO1 = 1;
//SPIRAM CS Chip Select
GPIO_SetupPinMux(19, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(19, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO19 = 1;
//DRV8874 #1 DIR Direction
GPIO_SetupPinMux(29, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(29, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO29 = 1;
//DRV8874 #2 DIR Direction
GPIO_SetupPinMux(32, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(32, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPBSET.bit.GPIO32 = 1;
//DAN28027 CS Chip Select
GPIO_SetupPinMux(9, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(9, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPASET.bit.GPIO9 = 1;
//MPU9250 CS Chip Select
GPIO_SetupPinMux(66, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(66, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPCSET.bit.GPIO66 = 1;
//WIZNET CS Chip Select
GPIO_SetupPinMux(125, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(125, GPIO_OUTPUT, GPIO_PUSHPULL);
GpioDataRegs.GPDSET.bit.GPIO125 = 1;
//PushButton 1
GPIO_SetupPinMux(4, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(4, GPIO_INPUT, GPIO_PULLUP);
//PushButton 2
GPIO_SetupPinMux(5, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(5, GPIO_INPUT, GPIO_PULLUP);
//PushButton 3
GPIO_SetupPinMux(6, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(6, GPIO_INPUT, GPIO_PULLUP);
//PushButton 4
GPIO_SetupPinMux(7, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(7, GPIO_INPUT, GPIO_PULLUP);
//Joy Stick Pushbutton
GPIO_SetupPinMux(8, GPIO_MUX_CPU1, 0);
GPIO_SetupPinOptions(8, GPIO_INPUT, GPIO_PULLUP);
//RC Servo 1 - EPWM8A
GPIO_SetupPinMux(14, GPIO_MUX_CPU1, 1);
GPIO_SetupPinOptions(14, GPIO_OUTPUT, GPIO_PUSHPULL);
//RC Servo 2 - EPWM8B
GPIO_SetupPinMux(15, GPIO_MUX_CPU1, 1);
GPIO_SetupPinOptions(15, GPIO_OUTPUT, GPIO_PUSHPULL);
GPIO_SetupPinMux(2, GPIO_MUX_CPU1, 1);
GPIO_SetupPinOptions(2, GPIO_OUTPUT, GPIO_PUSHPULL);
GPIO_SetupPinMux(3, GPIO_MUX_CPU1, 1);
GPIO_SetupPinOptions(3, GPIO_OUTPUT, GPIO_PUSHPULL);
GPIO_SetupPinMux(16, GPIO_MUX_CPU1, 5);
GPIO_SetupPinOptions(16, GPIO_OUTPUT, GPIO_PUSHPULL);
// ----- code for CAN start here -----
//GPIO17 - CANRXB
GPIO_SetupPinMux(17, GPIO_MUX_CPU1, 2);
GPIO_SetupPinOptions(17, GPIO_INPUT, GPIO_ASYNC);
//GPIO12 - CANTXB
GPIO_SetupPinMux(12, GPIO_MUX_CPU1, 2);
GPIO_SetupPinOptions(12, GPIO_OUTPUT, GPIO_PUSHPULL);
// ----- code for CAN end here -----
// JK-LB - Setup for the EPWM2A,2B, for motor control and EPWM9 for buzzer control.
EPwm2Regs.TBCTL.bit.CTRMODE = 0;
EPwm2Regs.TBCTL.bit.FREE_SOFT = 3;
EPwm2Regs.TBCTL.bit.PHSEN = 0;
EPwm2Regs.TBCTL.bit.CLKDIV = 0;
EPwm2Regs.TBCTR = 0;
EPwm2Regs.TBPRD = 2500;
EPwm2Regs.CMPA.bit.CMPA = 1250;
EPwm2Regs.CMPB.bit.CMPB = 1250;
EPwm2Regs.AQCTLA.bit.CAU = 1;
EPwm2Regs.AQCTLB.bit.CBU = 1;
EPwm2Regs.AQCTLA.bit.ZRO = 2;
EPwm2Regs.AQCTLB.bit.ZRO = 2;
EPwm2Regs.TBPHS.bit.TBPHS = 0;
//EPWM5 initialization - to be used as a timer for ADCA interrupt function
EALLOW;
EPwm5Regs.ETSEL.bit.SOCAEN = 0; // Disable SOC on A group
EPwm5Regs.TBCTL.bit.CTRMODE = 3; // freeze counter
EPwm5Regs.ETSEL.bit.SOCASEL = 2; // Select Event when counter equal to PRD
EPwm5Regs.ETPS.bit.SOCAPRD = 1; // Generate pulse on 1st event (�pulse� is the same as �trigger�)
EPwm5Regs.TBCTR = 0x0; // Clear counter
EPwm5Regs.TBPHS.bit.TBPHS = 0x0000; // Phase is 0
EPwm5Regs.TBCTL.bit.PHSEN = 0; // Disable phase loading
EPwm5Regs.TBCTL.bit.CLKDIV = 0; // divide by 1 50Mhz Clock
//EPwm5Regs.TBPRD = 50000; // Set Period to 1ms sample. Input clock is 50MHz.
// EPwm5Regs.TBPRD = 12500;//Exercise 4: set period to 0.25ms
EPwm5Regs.TBPRD = 50000; //Exercise 4: set period to 0.1ms
// Notice here that we are not setting CMPA or CMPB because we are not using the PWM signal
EPwm5Regs.ETSEL.bit.SOCAEN = 1; //enable SOCA
EPwm5Regs.TBCTL.bit.CTRMODE = 0; //unfreeze, and enter up count mode
EDIS;
// EPWM8A and B for RC Servo Control
EPwm8Regs.TBCTL.bit.CTRMODE = 0;
EPwm8Regs.TBCTL.bit.FREE_SOFT = 3;
EPwm8Regs.TBCTL.bit.PHSEN = 0;
EPwm8Regs.TBCTL.bit.CLKDIV = 4; // LB&JT - Set clkdiv to divide 50 MHz by 16, to get a clock rate of 3.125 MHz (Exercise 3)
EPwm8Regs.TBCTR = 0;
EPwm8Regs.TBPRD = 62500; // LB&JT - With clock rate of 3.125 MHz, counting to 62500 yields a period of 50 Hz (Exercise 3), and is within 16 bit max of 65535
//LB - A and B initilized
EPwm8Regs.CMPA.bit.CMPA = 62500*0.04; // Initialize latch servo to unlatched position
EPwm8Regs.CMPB.bit.CMPB = 62500*0.12; // Initialize rubberband servo to relaxed position
EPwm8Regs.AQCTLA.bit.CAU = 1;
EPwm8Regs.AQCTLB.bit.CBU = 1;
EPwm8Regs.AQCTLA.bit.ZRO = 2;
EPwm8Regs.AQCTLB.bit.ZRO = 2;
EPwm8Regs.TBPHS.bit.TBPHS = 0;
// EPWM9 Initialization for control of buzzer
// EPwm9Regs.TBCTL.bit.CTRMODE = 0;
// EPwm9Regs.TBCTL.bit.FREE_SOFT = 3;
// EPwm9Regs.TBCTL.bit.PHSEN = 0;
// EPwm9Regs.TBCTL.bit.CLKDIV = 1;
//
// EPwm9Regs.TBCTR = 0;
//
// EPwm9Regs.TBPRD = 2500;
//
//// EPwm9Regs.CMPA.bit.CMPA = 0;
//
// EPwm9Regs.AQCTLA.bit.CAU = 0; // LB&JT - ignore CMPA
// EPwm9Regs.AQCTLA.bit.ZRO = 3; // LB&JT - alternate between high and low every period for an average 50% duty cycle
//
// EPwm9Regs.TBPHS.bit.TBPHS = 0;
EALLOW;
AdcaRegs.ADCCTL2.bit.PRESCALE = 6; //set ADCCLK divider to /4
AdcSetMode(ADC_ADCA, ADC_RESOLUTION_12BIT, ADC_SIGNALMODE_SINGLE); //read calibration settings
AdcaRegs.ADCCTL1.bit.INTPULSEPOS = 1;
AdcaRegs.ADCCTL1.bit.ADCPWDNZ = 1;
DELAY_US(1000);
//Select the channels to convert and end of conversion flag
//Many statements commented out, To be used when using ADCA or ADCB
//ADCA // LB&JT - Enable SOC0 and SOC1 for ADCA
AdcaRegs.ADCSOC0CTL.bit.CHSEL = 2; //SOC0 will convert ADCINA2
AdcaRegs.ADCSOC0CTL.bit.ACQPS = 99; //sample window is acqps + 1 SYSCLK cycles = 500ns
AdcaRegs.ADCSOC0CTL.bit.TRIGSEL = 13;// EPWM5 ADCSOCA or another trigger you choose will trigger SOC0
AdcaRegs.ADCSOC1CTL.bit.CHSEL = 3; //SOC1 will convert ADCINA3
AdcaRegs.ADCSOC1CTL.bit.ACQPS = 99; //sample window is acqps + 1 SYSCLK cycles = 500ns
AdcaRegs.ADCSOC1CTL.bit.TRIGSEL = 13;// EPWM5 ADCSOCA or another trigger you choose will trigger SOC1
AdcaRegs.ADCINTSEL1N2.bit.INT1SEL = 1; //set to last SOC that is converted and it will set INT1 flag ADCA1
AdcaRegs.ADCINTSEL1N2.bit.INT1E = 1; //enable INT1 flag
AdcaRegs.ADCINTFLGCLR.bit.ADCINT1 = 1; //make sure INT1 flag is cleared
EDIS;
// ----- code for CAN start here -----
// Initialize the CAN controller
InitCANB();
// Set up the CAN bus bit rate to 1000 kbps
setCANBitRate(200000000, 1000000);
// Enables Interrupt line 0, Error & Status Change interrupts in CAN_CTL register.
CanbRegs.CAN_CTL.bit.IE0= 1;
CanbRegs.CAN_CTL.bit.EIE= 1;
// ----- code for CAN end here -----
// Clear all interrupts and initialize PIE vector table:
// Disable CPU interrupts
DINT;
// Initialize the PIE control registers to their default state.
// The default state is all PIE interrupts disabled and flags
// are cleared.
// This function is found in the F2837xD_PieCtrl.c file.
InitPieCtrl();
// Disable CPU interrupts and clear all CPU interrupt flags:
IER = 0x0000;
IFR = 0x0000;
// Initialize the PIE vector table with pointers to the shell Interrupt
// Service Routines (ISR).
// This will populate the entire table, even if the interrupt
// is not used in this example. This is useful for debug purposes.
// The shell ISR routines are found in F2837xD_DefaultIsr.c.
// This function is found in F2837xD_PieVect.c.
InitPieVectTable();
// Interrupts that are used in this example are re-mapped to
// ISR functions found within this project
EALLOW; // This is needed to write to EALLOW protected registers
PieVectTable.TIMER0_INT = &cpu_timer0_isr;
PieVectTable.TIMER1_INT = &cpu_timer1_isr;
PieVectTable.TIMER2_INT = &cpu_timer2_isr;
PieVectTable.SCIA_RX_INT = &RXAINT_recv_ready;
PieVectTable.SCIB_RX_INT = &RXBINT_recv_ready;
PieVectTable.SCIC_RX_INT = &RXCINT_recv_ready;
PieVectTable.SCID_RX_INT = &RXDINT_recv_ready;
PieVectTable.SCIA_TX_INT = &TXAINT_data_sent;
PieVectTable.SCIB_TX_INT = &TXBINT_data_sent;
PieVectTable.SCIC_TX_INT = &TXCINT_data_sent;
PieVectTable.SCID_TX_INT = &TXDINT_data_sent;
PieVectTable.SPIB_RX_INT = &SPIB_isr;
PieVectTable.EMIF_ERROR_INT = &SWI_isr;
// ----- code for CAN start here -----
PieVectTable.CANB0_INT = &can_isr;
// ----- code for CAN end here -----
PieVectTable.ADCA1_INT = &ADCA_ISR; // ADCA PIEvector table
EDIS; // This is needed to disable write to EALLOW protected registers
// Initialize the CpuTimers Device Peripheral. This function can be
// found in F2837xD_CpuTimers.c
InitCpuTimers();
// Configure CPU-Timer 0, 1, and 2 to interrupt every given period:
// 200MHz CPU Freq, Period (in uSeconds)
ConfigCpuTimer(&CpuTimer0, LAUNCHPAD_CPU_FREQUENCY, 1000);
ConfigCpuTimer(&CpuTimer1, LAUNCHPAD_CPU_FREQUENCY, 4000);
ConfigCpuTimer(&CpuTimer2, LAUNCHPAD_CPU_FREQUENCY, 40000);
// Enable CpuTimer Interrupt bit TIE
CpuTimer0Regs.TCR.all = 0x4000;
CpuTimer1Regs.TCR.all = 0x4000;
CpuTimer2Regs.TCR.all = 0x4000;
init_serialSCIA(&SerialA,115200);
setupSpib();
init_eQEPs(); //LB&JT Exercise 1 - call before EINT line and after init_serialSCIA
// Enable CPU int1 which is connected to CPU-Timer 0, CPU int13
// which is connected to CPU-Timer 1, and CPU int 14, which is connected
// to CPU-Timer 2: int 12 is for the SWI.
IER |= M_INT1;
IER |= M_INT6;
IER |= M_INT8; // SCIC SCID
IER |= M_INT9; // SCIA CANB
IER |= M_INT12;
IER |= M_INT13;
IER |= M_INT14;
// Enable TINT0 in the PIE: Group 1 interrupt 7
PieCtrlRegs.PIEIER1.bit.INTx7 = 1;
// Enable SWI in the PIE: Group 12 interrupt 9
PieCtrlRegs.PIEIER12.bit.INTx9 = 1;
PieCtrlRegs.PIEIER6.bit.INTx3 = 1; //SPiB
// ----- code for CAN start here -----
// Enable CANB in the PIE: Group 9 interrupt 7
PieCtrlRegs.PIEIER9.bit.INTx7 = 1;
// ----- code for CAN end here -----
// ----- code for CAN start here -----
// Enable the CAN interrupt signal
CanbRegs.CAN_GLB_INT_EN.bit.GLBINT0_EN = 1;
// ----- code for CAN end here -----
//enable Interrupt 1.1 for ADCA
PieCtrlRegs.PIEIER1.bit.INTx1 = 1;
init_serialSCIC(&SerialC,115200);
init_serialSCID(&SerialD,115200);
// Enable global Interrupts and higher priority real-time debug events
EINT; // Enable Global interrupt INTM
ERTM; // Enable Global realtime interrupt DBGM
// ----- code for CAN start here -----
// // Transmit Message
// // Initialize the transmit message object used for sending CAN messages.
// // Message Object Parameters:
// // Message Object ID Number: 0
// // Message Identifier: 0x1
// // Message Frame: Standard
// // Message Type: Transmit
// // Message ID Mask: 0x0
// // Message Object Flags: Transmit Interrupt
// // Message Data Length: 4 Bytes
// //
// CANsetupMessageObject(CANB_BASE, TX_MSG_OBJ_ID, 0x1, CAN_MSG_FRAME_STD,
// CAN_MSG_OBJ_TYPE_TX, 0, CAN_MSG_OBJ_TX_INT_ENABLE,
// TX_MSG_DATA_LENGTH);
// Measured Distance from 1
// Initialize the receive message object 1 used for receiving CAN messages.
// Message Object Parameters:
// Message Object ID Number: 1
// Message Identifier: 0x060b0101
// Message Frame: Standard
// Message Type: Receive
// Message ID Mask: 0x0
// Message Object Flags: Receive Interrupt
// Message Data Length: 8 Bytes (Note that DLC field is a "don't care"
// for a Receive mailbox)
//
CANsetupMessageObject(CANB_BASE, RX_MSG_OBJ_ID_1, 0x060b0101, CAN_MSG_FRAME_EXT,
CAN_MSG_OBJ_TYPE_RX, 0, CAN_MSG_OBJ_RX_INT_ENABLE,
RX_MSG_DATA_LENGTH);
// Measured Distance from 2
// Initialize the receive message object 2 used for receiving CAN messages.
// Message Object Parameters:
// Message Object ID Number: 2
// Message Identifier: 0x060b0102
// Message Frame: Standard
// Message Type: Receive
// Message ID Mask: 0x0
// Message Object Flags: Receive Interrupt
// Message Data Length: 8 Bytes (Note that DLC field is a "don't care"
// for a Receive mailbox)
//
CANsetupMessageObject(CANB_BASE, RX_MSG_OBJ_ID_2, 0x060b0103, CAN_MSG_FRAME_EXT,
CAN_MSG_OBJ_TYPE_RX, 0, CAN_MSG_OBJ_RX_INT_ENABLE,
RX_MSG_DATA_LENGTH);
// Measurement Quality from 1
// Initialize the receive message object 2 used for receiving CAN messages.
// Message Object Parameters:
// Message Object ID Number: 3
// Message Identifier: 0x060b0201
// Message Frame: Standard
// Message Type: Receive
// Message ID Mask: 0x0
// Message Object Flags: Receive Interrupt
// Message Data Length: 8 Bytes (Note that DLC field is a "don't care"
// for a Receive mailbox)
//
CANsetupMessageObject(CANB_BASE, RX_MSG_OBJ_ID_3, 0x060b0201, CAN_MSG_FRAME_EXT,
CAN_MSG_OBJ_TYPE_RX, 0, CAN_MSG_OBJ_RX_INT_ENABLE,
RX_MSG_DATA_LENGTH);
// Measurement Quality from 2
// Initialize the receive message object 2 used for receiving CAN messages.
// Message Object Parameters:
// Message Object ID Number: 4
// Message Identifier: 0x060b0202
// Message Frame: Standard
// Message Type: Receive
// Message ID Mask: 0x0
// Message Object Flags: Receive Interrupt
// Message Data Length: 8 Bytes (Note that DLC field is a "don't care"
// for a Receive mailbox)
//
CANsetupMessageObject(CANB_BASE, RX_MSG_OBJ_ID_4, 0x060b0203, CAN_MSG_FRAME_EXT,
CAN_MSG_OBJ_TYPE_RX, 0, CAN_MSG_OBJ_RX_INT_ENABLE,
RX_MSG_DATA_LENGTH);
//
// Start CAN module operations
//
CanbRegs.CAN_CTL.bit.Init = 0;
CanbRegs.CAN_CTL.bit.CCE = 0;
// // Initialize the transmit message object data buffer to be sent
// txMsgData[0] = 0x12;
// txMsgData[1] = 0x34;
// txMsgData[2] = 0x56;
// txMsgData[3] = 0x78;
...
This file has been truncated, please download it to see its full contents.
Comments
Please log in or sign up to comment.