/* This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version. This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details. You should have received a copy of the GNU General Public License along with this program. If not, see . */ /* * AP_MotorsSingle.cpp - ArduCopter motors library * Code by RandyMackay. DIYDrones.com * */ #include #include #include "AP_MotorsSingle.h" #include extern const AP_HAL::HAL& hal; // init void AP_MotorsSingle::init(motor_frame_class frame_class, motor_frame_type frame_type) { // make sure 6 output channels are mapped for (uint8_t i=0; i<6; i++) { add_motor_num(CH_1+i); } // set the motor_enabled flag so that the main ESC can be calibrated like other frame types motor_enabled[AP_MOTORS_MOT_5] = true; motor_enabled[AP_MOTORS_MOT_6] = true; // setup actuator scaling for (uint8_t i=0; i= _throttle_thrust_max) { throttle_thrust = _throttle_thrust_max; limit.throttle_upper = true; } throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, _throttle_thrust_max); float rp_thrust_max = MAX(fabsf(roll_thrust), fabsf(pitch_thrust)); // calculate how much roll and pitch must be scaled to leave enough range for the minimum yaw if (is_zero(rp_thrust_max)) { rp_scale = 1.0f; } else { rp_scale = constrain_float((1.0f - MIN(fabsf(yaw_thrust), (float)_yaw_headroom/1000.0f)) / rp_thrust_max, 0.0f, 1.0f); if (rp_scale < 1.0f) { limit.roll_pitch = true; } } actuator_allowed = 1.0f - rp_scale * rp_thrust_max; if (fabsf(yaw_thrust) > actuator_allowed) { yaw_thrust = constrain_float(yaw_thrust, -actuator_allowed, actuator_allowed); limit.yaw = true; } // combine roll, pitch and yaw on each actuator // front servo actuator[0] = rp_scale * roll_thrust - yaw_thrust; // right servo actuator[1] = rp_scale * pitch_thrust - yaw_thrust; // rear servo actuator[2] = -rp_scale * roll_thrust - yaw_thrust; // left servo actuator[3] = -rp_scale * pitch_thrust - yaw_thrust; // calculate the minimum thrust that doesn't limit the roll, pitch and yaw forces thrust_min_rpy = MAX(MAX(fabsf(actuator[0]), fabsf(actuator[1])), MAX(fabsf(actuator[2]), fabsf(actuator[3]))); thr_adj = throttle_thrust - throttle_avg_max; if (thr_adj < (thrust_min_rpy - throttle_avg_max)) { // Throttle can't be reduced to the desired level because this would mean roll or pitch control // would not be able to reach the desired level because of lack of thrust. thr_adj = MIN(thrust_min_rpy, throttle_avg_max) - throttle_avg_max; } // calculate the throttle setting for the lift fan _thrust_out = throttle_avg_max + thr_adj; if (is_zero(_thrust_out)) { limit.roll_pitch = true; limit.yaw = true; } // limit thrust out for calculation of actuator gains float thrust_out_actuator = constrain_float(MAX(_throttle_hover*0.5f,_thrust_out), 0.5f, 1.0f); // calculate the maximum allowed actuator output and maximum requested actuator output for (uint8_t i=0; i fabsf(actuator[i])) { actuator_max = fabsf(actuator[i]); } } if (actuator_max > thrust_out_actuator && !is_zero(actuator_max)) { // roll, pitch and yaw request can not be achieved at full servo defection // reduce roll, pitch and yaw to reduce the requested defection to maximum limit.roll_pitch = true; limit.yaw = true; rp_scale = thrust_out_actuator/actuator_max; } else { rp_scale = 1.0f; } // force of a lifting surface is approximately equal to the angle of attack times the airflow velocity squared // static thrust is proportional to the airflow velocity squared // therefore the torque of the roll and pitch actuators should be approximately proportional to // the angle of attack multiplied by the static thrust. for (uint8_t i=0; i