BroBot Code for ESE350 Lab6 part 3 (Skeleton)
Dependencies: MPU6050_V3 mbed-rtos mbed
Fork of BroBot_RTOS_ESE350 by
main.cpp
- Committer:
- csharer
- Date:
- 2017-01-24
- Revision:
- 14:94c65d1c8bad
- Parent:
- 13:a18d41a60d0b
- Child:
- 15:d6d7623a17f8
File content as of revision 14:94c65d1c8bad:
//BroBot V3 this is the most up to date, velocity is now working //Author: Carter Sharer //Date: 10/13/2016 //Added communication protocol v1 (no type selection) //Knob1 39.898 Knob2 44.381 Knob3 10.55 Knob4 18.67 //Knob1 13.418 Knob2 28.848 Knob3 9.45 Knob4 42.29 Good //Knob1 15.373 Knob2 28.261 Knob3 10.42 Knob4 40.97 Smoother /******************************* README USAGE ******************************* * This robot must be powered on while it is laying down flat on a still table * This allows the robot to calibrate the IMU (~5 seconds) * The motors are DISABLED when the robot tilts more then +-45 degrees from * vertical. To ENABLE the motors you must lift the robot to < +- 45 degres and * press the joystick button. * To reset the motor positions you must press the josystick button anytime. ******************************************************************************/ //Controller Values float knob1, knob2, knob3, knob4; float jstick_h, jstick_v; //Button bool button; //BroBot Begin #include "cmsis_os.h" #include "rtos_definations.h" #include "pin_assignments.h" #include "I2Cdev.h" #include "JJ_MPU6050_DMP_6Axis.h" #include "BroBot.h" #include "BroBot_IMU.h" #include "stepper_motors.h" #include "MRF24J40.h" #include "communication.h" //Angle Offset is used to set the natural balance point of your robot. //You should adjust this offset so that your robots balance points is near 0 #define ANGLE_OFFSET 107 #define MRF_CHANNEL 2 //For RF Communication #define JSTICK_H 8 #define JSTICK_V 9 #define SPACE 10 #define KNOB1 11 #define KNOB2 12 #define KNOB3 13 #define KNOB4 14 #define ANGLE 15 #define BUTTON 16 #define JSTICK_OFFSET 100 #define TX_BUFFER_LEN 18 #define TX_ANGLE_OFFSET 100 //Knobs #define POT1 p17 #define POT2 p18 #define POT3 p16 #define POT4 p15 //JoyStick #define POTV p19 #define POTH p20 //PID #define MAX_THROTTLE 580 #define MAX_STEERING 150 #define MAX_TARGET_ANGLE 12 #define KP 0.19 #define KD 28 #define KP_THROTTLE 0.01 //0.07 #define KI_THROTTLE 0//0.04 #define ITERM_MAX_ERROR 25 // Iterm windup constants for PI control //40 #define ITERM_MAX 8000 // 5000 #define GPIOA p21 #define GPIOB p22 #define GPIOC p23 #define GPIOD p24 #define THROTTLE_DAMPNER 100 #define VELOCITY_SAMPLES 1000 //*********** Local Function Definations BEGIN **************// void init_system(); void init_imu(); //*********** Local Function Definations END **************// Timer timer; int timer_value = 0; int timer_old = 0; float velocitySamples[VELOCITY_SAMPLES + 1] = {0.0}; Serial pc(USBTX, USBRX); // LEDs DigitalOut led1(LED1); DigitalOut led2(LED2); DigitalOut led3(LED3); DigitalOut led4(LED4); //GPIO Pins DigitalOut gpioMonitorA(GPIOA); DigitalOut gpioMonitorB(GPIOB); DigitalOut gpioMonitorC(GPIOC); DigitalOut gpioMonitorD(GPIOD); //Used to set angle upon startup bool initilizeAngle = true; // ================================================================ // === IMU Thread === // ================================================================ void imu_update_thread(void const *args) { pc.printf("Starting IMU Thread..\r\n"); while (1) { osSignalWait(IMU_UPDATE_SIGNAL,osWaitForever); //gpioMonitorA = 1; if(mpuInterrupt) { mpuInterrupt = false; led3 = !led3; /********************* All IMU Handling DO NOT MODIFY *****************/ //Disable IRQ //checkpin.rise(NULL); //reset interrupt flag and get INT_STATUS byte mpuIntStatus = mpu.getIntStatus(); //get current FIFO count fifoCount = mpu.getFIFOCount(); // check for overflow (this should never happen unless our code is too inefficient) if ((mpuIntStatus & 0x10) || fifoCount == 1024) { // reset so we can continue cleanly mpu.resetFIFO(); pc.printf("MPU FIFO overflow!"); //otherwise, check for DMP data ready interrupt (this should happen frequently) } else if (mpuIntStatus & 0x02) { //wait for correct available data length, should be a VERY short wait while (fifoCount < packetSize) fifoCount = mpu.getFIFOCount(); //read a packet from FIFO mpu.getFIFOBytes(fifoBuffer, packetSize); //track FIFO count here in case there is > 1 packet available //(this lets us immediately read more without waiting for an interrupt) fifoCount -= packetSize; //Read new angle from IMU new_angle = (float)(dmpGetPhi() - ANGLE_OFFSET); //Calculate the delta angle dAngle = new_angle - angle; //Filter out angle readings larger then MAX_ANGLE_DELTA if(initilizeAngle) { angle = new_angle; initilizeAngle = false; } else if( ((dAngle < 15) && (dAngle > -15))) { angle = new_angle; } else { pc.printf("\t\t\t Delta Angle too Large: %d. Ignored \r\n",dAngle); } } //gpioMonitorA = 0; /********************* All IMU Handling DO NOT MODIFY *****************/ }//End of if(mpuInterrupt) loop osSignalClear(imu_update_thread_ID,IMU_UPDATE_SIGNAL); osThreadYield(); // Yield to a running thread } } // ================================================================ // === PID Thread === // ================================================================ void pid_update_thread(void const *args) { float Kp1 = 0; float Kd1 = 0; float Kp2 = 0; float Kd2 = 0; float target_angle = 0; float target_angle_old = 0; float change_in_target_angle = 0; float change_in_angle = 0; float angle_old1 = 0; float angle_old2 = 0; float kp_term = 0; float kd_term = 0; float throttle = 0; float steering = 0; float control_output = 0; int robot_pos = 0; int loop_counter = 0; int velocitySamplesCounter = 0; int dt = 0; float error = 0; float velocity = 0; bool fallen = true; // --- For Position controller --- // float pos_error = 0; float kp_pos_term = 0; float kd_pos_term = 0; float change_in_target_pos = 0; float target_pos = 0; float target_pos_old = 0; float target_velocity = 0; float velocity_error = 0; float change_in_velocity = 0; float d_velocity = 0; float runningSumReplaceVal = 0; float newVelocity = 0; float velocitySum = 0; memset(velocitySamples,0,sizeof(velocitySamples)); pc.printf("Starting PID Thread..\r\n"); while(1) { gpioMonitorA = 1; //Get the time stamp as soon as it enters the loop timer_value = timer.read_us(); //led1 = led1^1; led4 = !fallen; led2 = button; if(jstick_v > 80) led3 = 1; else led3 = 0; //Button Press on the remote initilizes the robot position. if(button) { pos_M1 = 0; pos_M2 = 0; target_pos = 0; motor1 = 0; motor2 = 0; control_output = 0; fallen = false; } //Preset Knob Values for Green Balance Bot //knob1 = 1.132; //knob2 = 47.284; //knob3 = 18.46; //knob4 = 17.07; //Set Gainz with knobs Kp1 = ((float)knob1) / 100.0; Kd1 = ((float)knob2) / 1.0; Kp2 = ((float)knob3) / 1000.0; Kd2 = ((float)knob4) / 100.0; //Joystick control throttle = (float)jstick_v / THROTTLE_DAMPNER; steering = (float)jstick_h / 10.0; //Calculate the delta time dt = (timer_value - timer_old); timer_old = timer_value; angle_old = angle; // STANDING: Motor Control Enabled //******************** PID Control BEGIN ********************** // if(((angle < 45) && (angle > -45)) && (fallen == false)) { loop_counter++; //CS Pd Target Angle Contoller Goes Here //Robot Position robot_pos = (pos_M1 + pos_M2) / 2; target_pos += throttle/2; //Velocity Computation velocitySamplesCounter++; if(velocitySamplesCounter == VELOCITY_SAMPLES){ velocitySamplesCounter = 0; } runningSumReplaceVal = velocitySamples[velocitySamplesCounter]; //value to replace newVelocity = (motor1 + motor2) / 2; velocitySamples[velocitySamplesCounter] = newVelocity; //replace value with velocitySum = velocitySum - runningSumReplaceVal + newVelocity; velocity = velocitySum/VELOCITY_SAMPLES; //CS ***************** Position Controller ********************* //target_pos = 0; pos_error = robot_pos - target_pos; //robot_pos - target_pos; //KP Term kp_pos_term = Kp1 * pos_error; //KD Term change_in_target_pos = target_pos - target_pos_old; //kd_pos_term = ((-Kd2 * change_in_target_pos) + (-Kd2*change_in_pos)) /dt; kd_pos_term = ((Kd1 * change_in_target_pos) + (Kd1*velocity)); target_velocity = kp_pos_term; // + kd_pos_term; target_velocity = CAP(target_velocity, 100); //CS ***************** Velocity Controller ********************* //target_velocity = throttle; velocity_error = target_velocity - velocity; change_in_velocity = velocity - velocitySamples[(velocitySamplesCounter + 500)%VELOCITY_SAMPLES]; d_velocity = (Kd2 * change_in_velocity)/dt; /* if(target_velocity <= 3 && target_velocity >= -3) { target_angle = 0; } else{ } */ target_angle = (-velocity_error * Kp2 * 50); //+ d_velocity; //CS ************ PD Stability CONTROLLER HERE **************** //Knob1 7.373/1000.0 Knob2 50.986/1.0 float Kp1S = 7.373/1000.0; float Kd1S = 50.986/1.0; error = target_angle - angle; kp_term = Kp1S * error; change_in_target_angle = target_angle - target_angle_old; //add change_in_angle = angle - angle_old2; //add kd_term = ((Kd1S * change_in_target_angle) - (Kd1S*change_in_angle)) / dt; //kd_term = ((Kd1 * change_in_target_angle) - (Kd1*velocity)); //pc.printf("dAngle:%f\r\n", angle-angle_old1); //Control Output control_output += kp_term + kd_term; //-100 to 100 control_output = CAP(control_output, MAX_CONTROL_OUTPUT); // Limit max output from control motor1 = (int16_t)(control_output + (steering)); motor2 = (int16_t)(control_output - (steering)); motor1 = CAP(motor1, MAX_CONTROL_OUTPUT); motor2 = CAP(motor2, MAX_CONTROL_OUTPUT); //Update variables target_angle_old = target_angle; angle_old2 = angle_old1; angle_old1 = angle; //Enable Motors enable = ENABLE; setMotor1Speed(-motor1); //setMotor1Speed(20); //setMotor2Speed(40); setMotor2Speed(-motor2); //robot_pos += (-motor1 + -motor2) / 2; //pc.printf("m1: %d m2: %d angle: %0.1f, controlout: %f tAngle: %f dt: %f timer: %d \r\n", motor1, motor2, angle, control_output, target_angle, dt, timer_value); } else { //[FALLEN} //Disable Motors enable = DISABLE; //Set fallen flag fallen = true; } if(loop_counter >= 20) { gpioMonitorC = 1; loop_counter = 0; pc.printf("Target Vel: %f\r\n",target_velocity); //pc.printf("angle:%d Kp1: %0.3f Kd1: %0.2f Kp2: %0.2f Kd2: %0.3f tang: %0.2f dt:%d rob_pos: %d VE: %f\r\n", (int)angle, Kp1, Kd1, Kp2, Ki2, target_angle, dt, robot_pos, velocity_error); //pc.printf("Jstick_h: %d Jstick_v: %d Knob1 %d Knob2 %d Knob3 %d Knob4 %d Button: %d\r\n", jstick_h, jstick_v, knob1, knob2, knob3, knob4, button); //pc.printf("CAngle: %d, TAngle: %d,Pos: %d, dt: %d\r\n",(int)angle,target_angle,robot_pos,dt); //wait_us(200); gpioMonitorC = 0; } gpioMonitorA = 0; } //end main loop } // ================================================================ // === Communication Thread === // ================================================================ void communication_update_thread(void const *args) { pc.printf("Starting Communication Thread..\r\n"); while(1) { //Recieve Data //gpioMonitorC = 1; rxLen = rf_receive(rxBuffer, 128); if(rxLen > 0) { led1 = led1^1; //Process data with our protocal communication_protocal(rxLen); } osDelay(30); //gpioMonitorC = 0; } } // ================================================================ // === INITIAL SETUP === // ================================================================ void init_imu() { pc.printf("Start IMU Initilization.. \r\n"); // Manual MPU initialization... accel=2G, gyro=2000º/s, filter=20Hz BW, output=200Hz mpu.setClockSource(MPU6050_CLOCK_PLL_ZGYRO); mpu.setFullScaleGyroRange(MPU6050_GYRO_FS_2000); mpu.setFullScaleAccelRange(MPU6050_ACCEL_FS_2); mpu.setDLPFMode(MPU6050_DLPF_BW_10); //10,20,42,98,188 // Default factor for BROBOT:10 mpu.setRate(4); // 0=1khz 1=500hz, 2=333hz, 3=250hz [4=200hz]default mpu.setSleepEnabled(false); wait_ms(500); // load and configure the DMP devStatus = mpu.dmpInitialize(); if(devStatus == 0) { mpu.setDMPEnabled(true); mpuIntStatus = mpu.getIntStatus(); dmpReady = true; } else { // 1 = initial memory load failed // 2 = DMP configuration updates failed pc.printf("DMP INIT error \r\n"); } //Gyro Calibration wait_ms(500); pc.printf("Gyro calibration!! Dont move the robot in 1 second... \r\n"); wait_ms(500); // verify connection pc.printf(mpu.testConnection() ? "Connection Good \r\n" : "Connection Failed\r\n"); //Adjust Sensor Fusion Gain dmpSetSensorFusionAccelGain(0x20); wait_ms(200); mpu.resetFIFO(); } void init_system() { initilizeAngle = true; //Set the Channel. 0 is default, 15 is max mrf.SetChannel(MRF_CHANNEL); enable = DISABLE; //Disable Motors pc.baud(115200); pc.printf("Booting BroBot mbed RTOS..\r\n"); //Initilize the IMU init_imu(); //Attach Interupt for IMU on rising edge of checkpin checkpin.rise(&dmpDataReady); pc.printf("IMU Initilized..\r\n"); //Init Stepper Motors //Attach Motor Control Timer Call Back Functions timer_M1.attach_us(&ISR1, ZERO_SPEED);//1s Period timer_M2.attach_us(&ISR2, ZERO_SPEED);//1s Period step_M1 = 1; dir_M1 = 1; pc.printf("Motors Initilized..\r\n"); //Timers initilized timer.start(); timer_value = timer.read_us(); //Init GPIO Monitors gpioMonitorA = 0; gpioMonitorB = 0; gpioMonitorC = 0; gpioMonitorD = 0; enable = ENABLE; //Enable Motors } // ================================================================ // === MAIN PROGRAM LOOP === // ================================================================ int main() { init_system(); //Create IMU Thread imu_update_thread_ID = osThreadCreate(osThread(imu_update_thread), NULL); //Create PID Thread pid_update_thread_ID = osThreadCreate(osThread(pid_update_thread), NULL); //Create Communication Thread communication_update_thread_ID = osThreadCreate(osThread(communication_update_thread), NULL); } //End Main()