ESE350 project, Spring 2016, University of Pennsylvania
Dependencies: Adafruit9-DOf Receiver mbed-rtos mbed
quadcopter.cpp
- Committer:
- ivo_david_michelle
- Date:
- 2016-05-06
- Revision:
- 48:0346cdff12a7
- Parent:
- 47:ae478c380136
- Child:
- 49:59c3427e6838
File content as of revision 48:0346cdff12a7:
#include "quadcopter.h" #include "sensor.h" #include "receiver.h" #include <string> #ifndef M_PI #define M_PI 3.14159265358979323846 #endif DigitalOut initializationLED(LED3); // constructor Quadcopter::Quadcopter(Serial *pcPntr, MRF24J40 *mrfPntr, Timer *timer) { pc_= pcPntr; // enable printing g_= 9.81; l_= 0.25; gamma_= 1; //desired_mutex = desired; // control gains set s.t. 100% joystick results in 15% (actually: (maxPwm-zeroVelPwm+0.1)) duty cycle. kp_f_ = (MAX_PWM - OFF_PWM) * 4 / 0.5; kp_phi_ = 0.3 * (MAX_PWM - OFF_PWM) * l_ / 0.5 * 4 / M_PI; //0.3 quite slow kp_theta_ = 0.3 * (MAX_PWM - OFF_PWM) * l_ / 0.5 * 4 / M_PI; kp_psi_ = 0; // derivative attitude control gains // TODO 0.15 for both kd_phi_ = 0.1 * (MAX_PWM - OFF_PWM) * 2 / M_PI; // 0.25 maybe a good kd_theta_ = 0.4 * (MAX_PWM - OFF_PWM) * 2 / M_PI; kd_psi_ = 0.1; // incresae ki_phi ki_phi_ = 0 * (MAX_PWM - OFF_PWM)/(2*M_PI/4); // full control signal after 2s at pi/4 error ki_theta_ = 0 * (MAX_PWM - OFF_PWM)/(2*M_PI/4); i_e_phi_ = 0; i_e_theta_ = 0; comp_x_offset = 0; comp_y_offset = 0; max_integral_phi_ = 0.05/(ki_phi_ * (0.5/l_ + 0.25)); // influence of integral part smaller than 0.05 max_integral_theta_ = 0.05/(ki_theta_ * (0.5/l_ + 0.25)); // desired values (will come from joystick) F_des_ = 0; // desired thrust force (excluding weight compensation) dof_ = Adafruit_9DOF(); accel_ = Adafruit_LSM303_Accel_Unified(30301); //mag_ = Adafruit_LSM303_Mag_Unified(30302); gyro_ = Adafruit_L3GD20_Unified(20); // prepare for communication with remote control rcTimer_.start(); mrf_ = mrfPntr; // RF tranceiver to link with handheld. rcLength_ = 250; mrf_->SetChannel(3); //Set the Channel. 0 is default, 15 is max //initial_offsets_ = (offset*) malloc(sizeof(offset)); initSensors(*this); // IMU // define timer controlTimer = timer; controlTimer->start(); // initialze previous values to zero prev_controller_time_ = 0; prev_sensor_time = 0; start_sampling_time = 0; //readSensorValues(); //kalmanPitch.setAngle(state_.phi); // set initial pitch //§kalmanRoll.setAngle(state_.theta); // set initial theta //compAngleX = state_.phi; //compAngleY = state_.theta; // constant offset at props spinning in hover velocity /2 because of overcorrection } void Quadcopter::readSensorValues() { // precomputed gyro offsets double offset_gyro_x = -4.793711656441709e-04; double offset_gyro_y = 4.481595092024531e-06; double offset_gyro_z = -2.371472392638039e-05; double offset_acc_x = -0.270495085889571; double offset_acc_y = -0.053425306748466; double offset_acc_z = -0.520254558282190; if (prev_sensor_time == 0) { prev_sensor_time = controlTimer->read(); start_sampling_time = prev_sensor_time; return; } // get acceleration values accel_.getEvent(&accel_event_); // detract offsets form raw acceleromater data accel_event_.acceleration.x -= offset_acc_x; accel_event_.acceleration.y -= offset_acc_y; accel_event_.acceleration.z -= offset_acc_z; // compute orientation with correctet acc data dof_.accelGetOrientation(&accel_event_, &orientation_); // compute roll and pitch values double raw_phi = orientation_.roll * M_PI / 180; double raw_theta = orientation_.pitch * M_PI / 180; // get gyro values gyro_.getEvent(&gyro_event_); // detract offsets form raw gyro data gyro_event_.gyro.x -= offset_gyro_x; gyro_event_.gyro.y -= offset_gyro_y; gyro_event_.gyro.z -= offset_gyro_z; // compute rates double raw_p = gyro_event_.gyro.x * M_PI / 180; double raw_q = gyro_event_.gyro.y * M_PI / 180; double raw_r = gyro_event_.gyro.z * M_PI / 180; float time = controlTimer->read(); float dt = time - prev_sensor_time; // TODO problems with this? // Kalman Filter // state_.phi = kalmanRoll.getAngle(state_.phi * 180 / M_PI, state_.p * 180 / M_PI, dt) * M_PI / 180; // state_.theta = kalmanPitch.getAngle(state_.theta * 180 / M_PI, state_.q * 180 / M_PI, dt) * M_PI / 180; // state_.p = kalmanRoll.getRate() * M_PI / 180; // state_.q = kalmanPitch.getRate() * M_PI / 180; // complementary filter parameters double alphaX = 0.0002;//0.002; double alphaY = 0.0001; //maybe 0.0002; // different version of complementary filter //compAngleX = (1 - alphaX) * (compAngleX + raw_p * dt) + alphaX * raw_phi; // Calculate the angle using a Complimentary filter //compAngleY = (1 - alphaY) * (com pAngleY + raw_q * dt) + alphaY * raw_theta; compAngleX = (1 - alphaX) * (compAngleX + (raw_p + 8.446703927263016e-04) * dt) + alphaX * raw_phi; // hardcoded value compensates drift with alpha == 0. compAngleY = (1 - alphaY) * (compAngleY + (raw_q - 0.008936763695439) * dt) + alphaY * raw_theta; static int comp_avg_count = 0; static double comp_sum_x = 0.0; static double comp_sum_y = 0.0; static bool sample_finished = false; if (time - start_sampling_time < 5.0) { comp_sum_x += compAngleX; comp_sum_y += compAngleY; comp_avg_count++; } else if (!sample_finished) { comp_x_offset = comp_sum_x / comp_avg_count; comp_y_offset = comp_sum_y / comp_avg_count; sample_finished = true; initializationLED = 1; } // assign values to state state_.phi = compAngleX - comp_x_offset; state_.theta = compAngleY - comp_y_offset; state_.p = raw_p; state_.q = raw_q; state_.r = raw_r; prev_sensor_time = time; // Plotting /*pc_->printf("%f %f %f %f %f %f %f \r\n", prev_sensor_time, accel_event_.acceleration.x, accel_event_.acceleration.y, accel_event_.acceleration.z, gyro_event_.gyro.x, gyro_event_.gyro.y, gyro_event_.gyro.z); */ // static int count = 0; // if (count % 100 == 0) { // pc_->printf("%d\r\n", count); // } // count++; //pc_->printf("%f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f %f\r\n", prev_sensor_time, F_des_, desiredState_.psi, desiredState_.theta, desiredState_.phi, state_.psi, state_.theta, state_.phi,state_.r, state_.p, state_.q, compAngleX, compAngleY, raw_phi, raw_theta,accel_event_.acceleration.x, accel_event_.acceleration.y, accel_event_.acceleration.z, comp_x_offset, comp_y_offset); } void Quadcopter::controller() { float time = controlTimer->read(); if (prev_controller_time_ == 0) { prev_controller_time_ = time; return; } // PD controller double e_phi = desiredState_.phi - state_.phi; double e_theta = desiredState_.theta - state_.theta; float dt = time - prev_controller_time_; // integrate errors i_e_phi_ = i_e_phi_ + e_phi * dt; i_e_theta_ = i_e_theta_ + e_theta * dt; // limit integrals i_e_phi_ = min(max_integral_phi_, i_e_phi_); i_e_theta_ = min(max_integral_theta_, i_e_theta_); i_e_phi_ = max(-max_integral_phi_, i_e_phi_); i_e_theta_ = max(-max_integral_theta_, i_e_theta_); // compute control forces controlInput_.f = kp_f_ * F_des_; controlInput_.mx = kp_phi_ * e_phi + kd_phi_ * (desiredState_.p - state_.p) + ki_phi_ * i_e_phi_; controlInput_.my = kp_theta_ * e_theta + kd_theta_ * (desiredState_.q - state_.q) + ki_theta_ * i_e_theta_; controlInput_.mz = kd_psi_ * (desiredState_.r - state_.q); // feedforward desired yaw rate. // kp_psi_*(desiredState_.psi-state_.psi)+kd_psi_*(desiredState_.r-state_.r); // set pwm values double forcePerMotor = 0.25 * controlInput_.f; double yawMomentPerMotor = 0.25 / gamma_ * controlInput_.mz; double rollMomentPerMotor = 0.5 / l_ * controlInput_.mx; double pitchMomentPerMotor = 0.5 / l_ * controlInput_.my; motorPwm_.m1 = MIN_PWM_1 + forcePerMotor - pitchMomentPerMotor - yawMomentPerMotor; motorPwm_.m2 = MIN_PWM_2 + forcePerMotor + rollMomentPerMotor + yawMomentPerMotor; motorPwm_.m3 = MIN_PWM_3 + forcePerMotor + pitchMomentPerMotor - yawMomentPerMotor; motorPwm_.m4 = MIN_PWM_4 + forcePerMotor - rollMomentPerMotor + yawMomentPerMotor; // cut off at max PWM motorPwm_.m1 = min(MAX_PWM, motorPwm_.m1); motorPwm_.m2 = min(MAX_PWM, motorPwm_.m2); motorPwm_.m3 = min(MAX_PWM, motorPwm_.m3); motorPwm_.m4 = min(MAX_PWM, motorPwm_.m4); motorPwm_.m1 = max(MIN_PWM_1, motorPwm_.m1); motorPwm_.m2 = max(MIN_PWM_2, motorPwm_.m2); motorPwm_.m3 = max(MIN_PWM_3, motorPwm_.m3); motorPwm_.m4 = max(MIN_PWM_4, motorPwm_.m4); prev_controller_time_ = time; // Printing //pc_->printf("%f %f %f %f %f %f %f %f \r\n", time, F_des_, desiredState_.psi, desiredState_.theta, desiredState_.phi, state_.psi, state_.theta, state_.phi); //pc_->printf("m1: %f\tm2: %f\tm3: %f\tm4: %f\r\n", motorPwm_.m1, motorPwm_.m2, motorPwm_.m3, motorPwm_.m4); } motors Quadcopter::getPwm() { return motorPwm_; } state Quadcopter::getState() { return state_; } Adafruit_LSM303_Accel_Unified Quadcopter::getAccel() { return accel_; } //Adafruit_LSM303_Mag_Unified Quadcopter::getMag() //{ // return mag_; //} Adafruit_L3GD20_Unified Quadcopter::getGyro() { return gyro_; } offset* Quadcopter::getOffset() { return initial_offsets_; } Adafruit_9DOF Quadcopter::getIMU() { return dof_; } double Quadcopter::getForce() { return F_des_; } void Quadcopter::readRc() { uint8_t zero = 0; uint8_t *rssi = &zero; uint8_t receive = 0; char rxBuffer[rcLength_]; float thrust; float yaw = 0; float pitch = 0; float roll = 0; long long id; //static int thrust_outliers = 0; receive = rf_receive_rssi(*mrf_, rxBuffer, rssi, rcLength_ + 1); if (receive > 10) { int written = sscanf(rxBuffer, "%lld,%f,%f,%f,%f", &id, &thrust, &yaw, &pitch, &roll); // pc_->printf("%d\r\n", written); if (written != 5) { // pc_->printf("%s\r\n", rxBuffer); return; } } else { pc_->printf("Receive failure\r\n"); return; } // test for outliers (can remove when fixed for sure) // float temp_thrust = thrust - 0.5; // // if (temp_thrust < -0.3) { // thrust_outliers++; // if (thrust_outliers < 3) { // thrust = F_des_; // } // } else { // thrust_outliers = 0; // } // convert to radians, range is = +-40° or +-0.698132 radians desiredState_.phi = 1 * (-(roll * 30) * M_PI / 180); // minus, because joystick to right should result in positive moment desiredState_.theta = 1 * (pitch * 30) * M_PI / 180; desiredState_.r = 1 * yaw; // number between 0 and 1 //((yaw - 0.5) * 80) * M_PI / 180; F_des_ = thrust; // number between 0 and 1 -> number between -0.5 and 0.5 /* test for outliers (can remove when fixed for sure) if (abs(F_des_) > 0.01 || abs(desiredState_.psi) > 0.01 || abs(desiredState_.theta) > 0.02 || abs(desiredState_.phi) > 0.01) { pc_->printf("%lld: thrust: %f yaw: %f pitch: %f roll: %f\r\n", id, F_des_, desiredState_.psi, desiredState_.theta, desiredState_.phi); //, thrust_outliers); } */ }