/* 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_MotorsCoax.h" #include extern const AP_HAL::HAL& hal; // init void AP_MotorsCoax::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), 0.5f*(float)_yaw_headroom/1000.0f)) / rp_thrust_max, 0.0f, 1.0f); if (rp_scale < 1.0f) { limit.roll_pitch = true; } } actuator_allowed = 2.0f * (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; } // calculate the minimum thrust that doesn't limit the roll, pitch and yaw forces thrust_min_rpy = MAX(fabsf(rp_scale * rp_thrust_max), fabsf(yaw_thrust)); 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 reduce airflow over // the control surfaces preventing roll and pitch reaching the desired level. 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 (fabsf(yaw_thrust) > thrust_out) { yaw_thrust = constrain_float(yaw_thrust, -thrust_out, thrust_out); limit.yaw = true; } _thrust_yt_ccw = thrust_out + 0.5f * yaw_thrust; _thrust_yt_cw = thrust_out - 0.5f * yaw_thrust; // 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); if (is_zero(thrust_out)) { limit.roll_pitch = true; } // 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. _actuator_out[0] = roll_thrust/thrust_out_actuator; _actuator_out[1] = pitch_thrust/thrust_out_actuator; if (fabsf(_actuator_out[0]) > 1.0f) { limit.roll_pitch = true; _actuator_out[0] = constrain_float(_actuator_out[0], -1.0f, 1.0f); } if (fabsf(_actuator_out[1]) > 1.0f) { limit.roll_pitch = true; _actuator_out[1] = constrain_float(_actuator_out[1], -1.0f, 1.0f); } _actuator_out[2] = -_actuator_out[0]; _actuator_out[3] = -_actuator_out[1]; } // output_test_seq - spin a motor at the pwm value specified // motor_seq is the motor's sequence number from 1 to the number of motors on the frame // pwm value is an actual pwm value that will be output, normally in the range of 1000 ~ 2000 void AP_MotorsCoax::output_test_seq(uint8_t motor_seq, int16_t pwm) { // exit immediately if not armed if (!armed()) { return; } // output to motors and servos switch (motor_seq) { case 1: // flap servo 1 rc_write(AP_MOTORS_MOT_1, pwm); break; case 2: // flap servo 2 rc_write(AP_MOTORS_MOT_2, pwm); break; case 3: // flap servo 3 rc_write(AP_MOTORS_MOT_3, pwm); break; case 4: // flap servo 4 rc_write(AP_MOTORS_MOT_4, pwm); break; case 5: // motor 1 rc_write(AP_MOTORS_MOT_5, pwm); break; case 6: // motor 2 rc_write(AP_MOTORS_MOT_6, pwm); break; default: // do nothing break; } }