Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/simulink/arducopter/functions/getMotorMixerFactors.m
Views: 1799
% Function to get the copters number of motors and there configuration to1% calculate the motor mixer factors for roll, pitch and yaw2%3% Fabian Bredemeier - IAV GmbH4% License: GPL v35function [num_motors, axis_facs_motors] = getMotorMixerFactors(frame_class, frame_type)6d2r = pi/180;7axis_facs_motors = struct;8num_motors = 0;9% Preliminary cell array for the motors axis factors consisting of the10% roll/pitch factor in degree (first element of cells) and the yaw11% factor12axis_facs_motors_pre = cell(0,0);1314%% Get configuration1516switch frame_class17case 1 % Quad18num_motors = 4;19axis_facs_motors_pre = cell(4,1);20switch frame_type21case 0 % Plus22axis_facs_motors_pre = { [90, 1]; [-90, 1]; [0, -1]; [180, -1] };23case 1 % X24axis_facs_motors_pre = { [45, 1]; [-135, 1]; [-45, -1]; [135, -1] };25case 2 % V26axis_facs_motors_pre = { [45, 0.7981]; [-135, 1.0]; [-45, -0.7981]; [135, -1.0] };27case 3 % H28axis_facs_motors_pre = { [45, -1]; [-135, -1]; [-45, 1]; [135, 1] };29case 13 % DJIX30axis_facs_motors_pre = { [45, 1]; [-45, -1]; [-135, 1]; [135, -1] };31case 14 % Clockwise ordering32axis_facs_motors_pre = { [45, 1]; [135, -1]; [-135, 1]; [-45, -1] };33end34case 2 % Hexa35num_motors = 6;36case {3, 4} % Octa and OctaQuad37num_motors = 8;38axis_facs_motors_pre = cell(8,1);39switch frame_type40case 0 % Plus41axis_facs_motors_pre = { [0, -1]; [180, -1]; [45, 1]; [135, 1]; ...42[-45, 1]; [-135, 1]; [-90, -1]; [90, -1] };43case 1 % X44axis_facs_motors_pre = { [22.5, -1]; [-157.5, -1]; [67.5, 1]; [157.5, 1]; ...45[-22.5, 1]; [-122.5, 1]; [-67.5, -1]; [112.5, -1] };46case 2 % V47axis_facs_motors_pre = { [0.83, 0.34, -1]; [-0.67, -0.32, -1]; [0.67, -0.32, 1]; [-0.50, -1.00, 1]; ...48[1.00, 1.00, 1]; [-0.83, 0.34, 1]; [-1.00, 1.00, -1]; [0.5, -1.00, -1] };49end50case 5 % Y651num_motors = 6;52case 12 % DodecaHexa53num_motors = 12;54case 14 % Deca55num_motors = 14;56end5758%% Check if configuration is defined59% Leave function if frame class is not configured yet60if num_motors == 061disp("Frame class unknown. Please add the configuration to the function.");62return;63end64% Leave function if axis factors are not yet defined for frame65if isempty(axis_facs_motors_pre)66disp("Motor axis factors are not yet defined for frame class!");67disp("The factors can be found in the setup_motors function within AP_MotorsMatrix.cpp.");68return;69end7071%% Calculate axis factors (roll/pitch) from preliminary array72% Create the output struct that stores the factors for the different73% axis in separate arrays. Each column of the subarrays represents one motor.74axis_facs_motors = struct('roll', zeros(1,num_motors), ...75'pitch', zeros(1,num_motors), ...76'yaw', zeros(1,num_motors) , ...77'throttle', zeros(1, num_motors) );78for i=1:num_motors79% Check if factors for roll and pitch are defined separately and80% therefore in radian -> dimension of a cell would be 381if ( length(axis_facs_motors_pre{i}) >= 3 )82axis_facs_motors.roll(1,i) = axis_facs_motors_pre{i}(1);83axis_facs_motors.pitch(1,i) = axis_facs_motors_pre{i}(2);84else85axis_facs_motors.roll(1,i) = cos( (axis_facs_motors_pre{i}(1)+90)*d2r );86axis_facs_motors.pitch(1,i) = cos( (axis_facs_motors_pre{i}(1))*d2r );87end88% The factors for yaw can be acquired directly from the preliminary89% array90axis_facs_motors.yaw(1,i) = axis_facs_motors_pre{i}(2);91% The factors for throttle are 1.0 by default (see AP_MotorsMatrix.h,92% line 87)93axis_facs_motors.throttle(1,i) = 1.0;94end9596%% Normalization of factors (AP_MotorsMatrix.cpp, line 1218)97roll_fac_max = 0.0;98pitch_fac_max = 0.0;99yaw_fac_max = 0.0;100throttle_fac_max = 0.0;101102% Find maximum factor103for i=1:num_motors104roll_fac_max = max(roll_fac_max, axis_facs_motors.roll(1,i));105pitch_fac_max = max(pitch_fac_max, axis_facs_motors.pitch(1,i));106yaw_fac_max = max(yaw_fac_max, axis_facs_motors.yaw(1,i));107throttle_fac_max = max(throttle_fac_max, axis_facs_motors.throttle(1,i));108end109110% Scale factors back to -0.5 to +0.5 for each axis111for i=1:num_motors112if(roll_fac_max ~= 0)113axis_facs_motors.roll(1,i) = 0.5 * axis_facs_motors.roll(1,i) / roll_fac_max;114end115if(pitch_fac_max ~= 0)116axis_facs_motors.pitch(1,i) = 0.5 * axis_facs_motors.pitch(1,i) / pitch_fac_max;117end118if(yaw_fac_max ~= 0)119axis_facs_motors.yaw(1,i) = 0.5 * axis_facs_motors.yaw(1,i) / yaw_fac_max;120end121if(throttle_fac_max ~= 0)122axis_facs_motors.throttle(1,i) = 0.5 * axis_facs_motors.throttle(1,i) / throttle_fac_max;123end124end125end126127