开关磁阻电机控制系统仿真与设计的MATLAB/Simulink实现方案

开关磁阻电机控制系统概述

开关磁阻电机是一种结构简单、成本低廉、可靠性高的电机,但其非线性特性使得控制系统设计具有挑战性。

1. SRM基本原理与数学模型

classdef SRM_Model < handle
    properties
        % 电机结构参数
        N_ph = 4          % 相数
        N_r = 8           % 转子极数
        N_s = 6           % 定子极数
        beta_s = 15       % 定子极弧 (度)
        beta_r = 17       % 转子极弧 (度)
        
        % 电气参数
        R_ph = 0.1        % 相电阻 (Ω)
        L_min = 0.01      % 最小电感 (H)
        L_max = 0.1       % 最大电感 (H)
        theta_aligned = 0 % 对齐位置 (度)
        theta_unaligned = 22.5 % 不对齐位置 (度)
        
        % 机械参数
        J = 0.01          % 转动惯量 (kg·m²)
        B = 0.001         % 摩擦系数 (N·m·s/rad)
        T_load = 5        % 负载转矩 (N·m)
    end
    
    methods
        function obj = SRM_Model()
            % 构造函数
        end
        
        function L = inductance(obj, theta, i)
            % 计算电感 - 基于位置和电流的非线性模型
            theta_elec = mod(theta * obj.N_r, 360);
            theta_overlap = obj.beta_s + obj.beta_r;
            
            % 归一化位置 (0到1,0为不对齐,1为对齐)
            if theta_elec <= obj.theta_unaligned
                x_norm = 0;
            elseif theta_elec >= obj.theta_aligned + 360/obj.N_r
                x_norm = 1;
            else
                x_norm = (theta_elec - obj.theta_unaligned) / ...
                        (obj.theta_aligned + 360/obj.N_r - obj.theta_unaligned);
            end
            
            % 饱和效应
            i_sat = 10; % 饱和电流 (A)
            k_sat = 1 - exp(-abs(i)/i_sat);
            
            % 电感计算
            L = obj.L_min + (obj.L_max - obj.L_min) * x_norm * (1 - 0.3 * k_sat);
        end
        
        function dL_dtheta = inductance_gradient(obj, theta, i)
            % 计算电感对位置的变化率
            h = 0.1; % 微小变化量 (度)
            L1 = obj.inductance(theta - h/2, i);
            L2 = obj.inductance(theta + h/2, i);
            dL_dtheta = (L2 - L1) / (h * pi/180); % H/rad
        end
        
        function torque = phase_torque(obj, theta, i)
            % 计算单相转矩
            dL_dtheta = obj.inductance_gradient(theta, i);
            torque = 0.5 * i^2 * dL_dtheta;
        end
        
        function [theta, omega, i_ph] = simulate_dynamics(obj, V_dc, switching_angles, i_ref, dt, duration)
            % 电机动态仿真
            time = 0:dt:duration;
            n_steps = length(time);
            
            % 初始化状态变量
            theta = zeros(1, n_steps);
            omega = zeros(1, n_steps);
            i_ph = zeros(obj.N_ph, n_steps);
            torque = zeros(1, n_steps);
            
            % 初始条件
            theta(1) = 0;
            omega(1) = 0;
            
            for k = 1:n_steps-1
                % 计算总转矩
                total_torque = 0;
                for ph = 1:obj.N_ph
                    % 计算转子位置相对于该相的角度
                    theta_ph = mod(theta(k) + (ph-1)*(360/obj.N_ph), 360);
                    
                    % 开关逻辑
                    [turn_on, turn_off] = obj.get_switching_angles(switching_angles, ph);
                    is_on = obj.check_conduction(theta_ph, turn_on, turn_off);
                    
                    if is_on && i_ph(ph, k) < i_ref
                        V_ph = V_dc;  % 开通
                    else
                        V_ph = -V_dc; % 关断或斩波
                    end
                    
                    % 电流微分方程
                    L = obj.inductance(theta_ph, i_ph(ph, k));
                    dL_dtheta = obj.inductance_gradient(theta_ph, i_ph(ph, k));
                    
                    di_dt = (V_ph - obj.R_ph * i_ph(ph, k) - ...
                            i_ph(ph, k) * dL_dtheta * omega(k)) / L;
                    
                    i_ph(ph, k+1) = i_ph(ph, k) + di_dt * dt;
                    
                    % 相转矩
                    phase_torque = obj.phase_torque(theta_ph, i_ph(ph, k));
                    total_torque = total_torque + phase_torque;
                end
                
                % 机械系统微分方程
                domega_dt = (total_torque - obj.T_load - obj.B * omega(k)) / obj.J;
                dtheta_dt = omega(k);
                
                omega(k+1) = omega(k) + domega_dt * dt;
                theta(k+1) = mod(theta(k) + dtheta_dt * dt, 360);
                torque(k) = total_torque;
            end
            torque(end) = torque(end-1);
        end
        
        function [turn_on, turn_off] = get_switching_angles(obj, switching_angles, phase)
            % 获取开关角度
            turn_on = switching_angles(phase, 1);
            turn_off = switching_angles(phase, 2);
        end
        
        function is_on = check_conduction(obj, theta_ph, turn_on, turn_off)
            % 检查导通状态
            if turn_on < turn_off
                is_on = (theta_ph >= turn_on) && (theta_ph <= turn_off);
            else
                % 处理跨周期情况
                is_on = (theta_ph >= turn_on) || (theta_ph <= turn_off);
            end
        end
    end
end

2. 功率变换器设计

classdef SRM_PowerConverter < handle
    properties
        V_dc = 300        % 直流母线电压 (V)
        f_sw = 20e3       % 开关频率 (Hz)
        topology = 'asymmetric_bridge' % 拓扑结构
    end
    
    methods
        function [V_ph, states] = control_phase(obj, phase_current, ref_current, theta_ph, turn_on, turn_off, control_mode)
            % 相控控制
            % control_mode: 'voltage_control', 'current_control', 'chopping_control'
            
            is_conduction_angle = (theta_ph >= turn_on) && (theta_ph <= turn_off);
            
            switch control_mode
                case 'voltage_control'
                    % 电压控制模式
                    if is_conduction_angle
                        V_ph = obj.V_dc;
                        states = 'power';
                    else
                        V_ph = -obj.V_dc;
                        states = 'brake';
                    end
                    
                case 'current_control'
                    % 电流斩波控制
                    hysteresis_band = 0.1; % A
                    
                    if is_conduction_angle
                        if phase_current < ref_current - hysteresis_band
                            V_ph = obj.V_dc;
                            states = 'power';
                        elseif phase_current > ref_current + hysteresis_band
                            V_ph = -obj.V_dc;
                            states = 'brake';
                        else
                            V_ph = 0;
                            states = 'freewheel';
                        end
                    else
                        V_ph = -obj.V_dc;
                        states = 'brake';
                    end
                    
                case 'pwm_control'
                    % PWM控制
                    if is_conduction_angle
                        duty_cycle = min(1, max(0, ref_current / 20)); % 简化
                        V_ph = obj.V_dc * duty_cycle;
                        states = 'pwm';
                    else
                        V_ph = -obj.V_dc;
                        states = 'brake';
                    end
                    
                otherwise
                    V_ph = 0;
                    states = 'off';
            end
        end
        
        function plot_switching_waveform(obj, time, theta, currents, voltages, phase)
            % 绘制开关波形
            figure('Position', [100, 100, 1200, 800]);
            
            subplot(4,1,1);
            plot(time, theta, 'b-', 'LineWidth', 1.5);
            ylabel('转子位置 (度)');
            title('SRM开关波形');
            grid on;
            
            subplot(4,1,2);
            plot(time, currents(phase,:), 'r-', 'LineWidth', 1.5);
            ylabel(['相', num2str(phase), '电流 (A)']);
            grid on;
            
            subplot(4,1,3);
            plot(time, voltages(phase,:), 'g-', 'LineWidth', 1.5);
            ylabel(['相', num2str(phase), '电压 (V)']);
            grid on;
            
            subplot(4,1,4);
            torque = zeros(size(time));
            for i = 1:length(time)
                % 计算转矩
                torque(i) = 0.5 * currents(phase,i)^2 * 0.05; % 简化
            end
            plot(time, torque, 'm-', 'LineWidth', 1.5);
            ylabel('转矩 (N·m)');
            xlabel('时间 (s)');
            grid on;
        end
    end
end

3. 控制系统设计

classdef SRM_Controller < handle
    properties
        % PID控制器参数
        Kp_speed = 0.5
        Ki_speed = 0.1
        Kd_speed = 0.01
        
        Kp_current = 1.0
        Ki_current = 0.5
        Kd_current = 0.001
        
        % 控制参数
        switching_angles = [10, 30;  % 相1: 开通角, 关断角
                           40, 60;   % 相2
                           70, 90;   % 相3
                           100, 120] % 相4
        
        control_mode = 'current_control'
        max_current = 15 % 最大相电流 (A)
    end
    
    methods
        function i_ref = speed_controller(obj, omega_ref, omega_actual, dt)
            % 速度PID控制器
            persistent integral_error last_error
            if isempty(integral_error)
                integral_error = 0;
                last_error = 0;
            end
            
            error = omega_ref - omega_actual;
            integral_error = integral_error + error * dt;
            derivative_error = (error - last_error) / dt;
            
            % PID输出
            i_ref = obj.Kp_speed * error + obj.Ki_speed * integral_error + ...
                   obj.Kd_speed * derivative_error;
            
            % 电流限幅
            i_ref = max(0, min(i_ref, obj.max_current));
            
            last_error = error;
        end
        
        function duty = current_controller(obj, i_ref, i_actual, dt)
            % 电流PID控制器
            persistent integral_error last_error
            if isempty(integral_error)
                integral_error = 0;
                last_error = 0;
            end
            
            error = i_ref - i_actual;
            integral_error = integral_error + error * dt;
            derivative_error = (error - last_error) / dt;
            
            duty = obj.Kp_current * error + obj.Ki_current * integral_error + ...
                   obj.Kd_current * derivative_error;
            
            duty = max(0, min(duty, 1));
            last_error = error;
        end
        
        function optimize_switching_angles(obj, omega, torque_demand)
            % 优化开关角度 - 基于转速和转矩需求
            if omega < 100
                % 低速模式 - 提前开通
                advance_angle = 5;
            elseif omega < 500
                advance_angle = 3;
            else
                % 高速模式 - 更大提前角
                advance_angle = 8;
            end
            
            % 更新开关角度
            for ph = 1:4
                obj.switching_angles(ph, 1) = 10 + (ph-1)*30 - advance_angle;
                obj.switching_angles(ph, 2) = 30 + (ph-1)*30;
            end
        end
        
        function plot_control_performance(obj, time, references, actuals, control_signals)
            % 绘制控制性能
            figure('Position', [100, 100, 1200, 600]);
            
            subplot(2,2,1);
            plot(time, references.omega, 'b--', 'LineWidth', 2); hold on;
            plot(time, actuals.omega, 'r-', 'LineWidth', 1.5);
            ylabel('转速 (rad/s)');
            legend('参考', '实际');
            title('速度控制');
            grid on;
            
            subplot(2,2,2);
            plot(time, references.current, 'b--', 'LineWidth', 2); hold on;
            plot(time, actuals.current, 'r-', 'LineWidth', 1.5);
            ylabel('电流 (A)');
            legend('参考', '实际');
            title('电流控制');
            grid on;
            
            subplot(2,2,3);
            plot(time, control_signals.duty, 'g-', 'LineWidth', 1.5);
            ylabel('占空比');
            xlabel('时间 (s)');
            title('控制信号');
            grid on;
            
            subplot(2,2,4);
            plot(time, actuals.torque, 'm-', 'LineWidth', 1.5);
            ylabel('转矩 (N·m)');
            xlabel('时间 (s)');
            title('输出转矩');
            grid on;
        end
    end
end

4. 完整的SRM仿真系统

classdef SRM_Simulation < handle
    properties
        motor
        converter
        controller
        simulation_params = struct()
        results = struct()
    end
    
    methods
        function obj = SRM_Simulation()
            % 初始化仿真系统
            obj.motor = SRM_Model();
            obj.converter = SRM_PowerConverter();
            obj.controller = SRM_Controller();
            obj.init_simulation_parameters();
        end
        
        function init_simulation_parameters(obj)
            % 初始化仿真参数
            obj.simulation_params.dt = 1e-5;      % 仿真步长
            obj.simulation_params.duration = 0.1; % 仿真时长
            obj.simulation_params.V_dc = 300;     % 直流电压
        end
        
        function run_simulation(obj, scenario)
            % 运行仿真
            % scenario: 'startup', 'speed_change', 'load_change'
            
            fprintf('开始SRM仿真: %s\n', scenario);
            
            dt = obj.simulation_params.dt;
            duration = obj.simulation_params.duration;
            time = 0:dt:duration;
            n_steps = length(time);
            
            % 初始化状态变量
            omega_ref = zeros(1, n_steps);
            omega_actual = zeros(1, n_steps);
            i_ref = zeros(1, n_steps);
            i_actual = zeros(4, n_steps);
            torque = zeros(1, n_steps);
            theta = zeros(1, n_steps);
            
            % 初始条件
            omega_actual(1) = 0;
            theta(1) = 0;
            
            % 根据场景设置参考信号
            [omega_ref, load_torque] = obj.generate_reference_signals(scenario, time);
            
            for k = 1:n_steps-1
                % 更新负载转矩
                obj.motor.T_load = load_torque(k);
                
                % 速度控制
                i_ref(k) = obj.controller.speed_controller(omega_ref(k), omega_actual(k), dt);
                
                % 优化开关角度
                obj.controller.optimize_switching_angles(omega_actual(k), i_ref(k));
                
                % 相电流控制
                for ph = 1:4
                    theta_ph = mod(theta(k) + (ph-1)*90, 360);
                    [turn_on, turn_off] = obj.controller.get_switching_angles(...
                        obj.controller.switching_angles, ph);
                    
                    % 电流控制
                    duty = obj.controller.current_controller(i_ref(k), i_actual(ph,k), dt);
                    
                    % 功率变换器
                    V_ph = obj.converter.V_dc * duty;
                    
                    % 电机动态 (简化)
                    L = obj.motor.inductance(theta_ph, i_actual(ph,k));
                    dL_dtheta = obj.motor.inductance_gradient(theta_ph, i_actual(ph,k));
                    
                    di_dt = (V_ph - obj.motor.R_ph * i_actual(ph,k) - ...
                            i_actual(ph,k) * dL_dtheta * omega_actual(k)) / L;
                    
                    i_actual(ph,k+1) = i_actual(ph,k) + di_dt * dt;
                    
                    % 计算转矩
                    phase_torque = obj.motor.phase_torque(theta_ph, i_actual(ph,k));
                    torque(k) = torque(k) + phase_torque;
                end
                
                % 机械系统
                domega_dt = (torque(k) - obj.motor.T_load - obj.motor.B * omega_actual(k)) / obj.motor.J;
                dtheta_dt = omega_actual(k);
                
                omega_actual(k+1) = omega_actual(k) + domega_dt * dt;
                theta(k+1) = mod(theta(k) + dtheta_dt * dt * 180/pi, 360);
            end
            
            % 存储结果
            obj.results.time = time;
            obj.results.omega_ref = omega_ref;
            obj.results.omega_actual = omega_actual;
            obj.results.i_ref = i_ref;
            obj.results.i_actual = i_actual;
            obj.results.torque = torque;
            obj.results.theta = theta;
            
            fprintf('仿真完成\n');
        end
        
        function [omega_ref, load_torque] = generate_reference_signals(obj, scenario, time)
            % 生成参考信号
            switch scenario
                case 'startup'
                    % 启动过程
                    omega_ref = 100 * (1 - exp(-time/0.02)); % 斜坡启动
                    load_torque = 2 * ones(size(time));
                    
                case 'speed_change'
                    % 速度变化
                    omega_ref = 50 + 50 * square(2*pi*5*time);
                    load_torque = 3 * ones(size(time));
                    
                case 'load_change'
                    % 负载变化
                    omega_ref = 100 * ones(size(time));
                    load_torque = 2 + 1 * (time > 0.05);
                    
                otherwise
                    omega_ref = 100 * ones(size(time));
                    load_torque = 2 * ones(size(time));
            end
        end
        
        function plot_simulation_results(obj)
            % 绘制仿真结果
            time = obj.results.time;
            
            figure('Position', [100, 100, 1400, 1000]);
            
            % 速度响应
            subplot(3,3,1);
            plot(time, obj.results.omega_ref, 'b--', 'LineWidth', 2); hold on;
            plot(time, obj.results.omega_actual, 'r-', 'LineWidth', 1.5);
            ylabel('转速 (rad/s)');
            legend('参考', '实际');
            title('速度响应');
            grid on;
            
            % 电流参考与实际
            subplot(3,3,2);
            plot(time, obj.results.i_ref, 'b--', 'LineWidth', 2); hold on;
            for ph = 1:4
                plot(time, obj.results.i_actual(ph,:), '-', 'LineWidth', 1);
            end
            ylabel('电流 (A)');
            title('相电流');
            legend('参考', '相1', '相2', '相3', '相4');
            grid on;
            
            % 转矩
            subplot(3,3,3);
            plot(time, obj.results.torque, 'm-', 'LineWidth', 1.5);
            ylabel('转矩 (N·m)');
            title('输出转矩');
            grid on;
            
            % 转子位置
            subplot(3,3,4);
            plot(time, obj.results.theta, 'g-', 'LineWidth', 1.5);
            ylabel('转子位置 (度)');
            xlabel('时间 (s)');
            title('转子位置');
            grid on;
            
            % 相1详细波形
            subplot(3,3,5);
            plot(time, obj.results.i_actual(1,:), 'r-', 'LineWidth', 1.5);
            ylabel('相1电流 (A)');
            xlabel('时间 (s)');
            title('相1电流波形');
            grid on;
            
            % 速度误差
            subplot(3,3,6);
            error = obj.results.omega_ref - obj.results.omega_actual;
            plot(time, error, 'k-', 'LineWidth', 1.5);
            ylabel('速度误差 (rad/s)');
            xlabel('时间 (s)');
            title('速度跟踪误差');
            grid on;
            
            % 电流轨迹
            subplot(3,3,7);
            theta_rad = obj.results.theta * pi/180;
            polarplot(theta_rad, obj.results.i_actual(1,:), 'r-');
            title('电流-位置轨迹');
            
            % 转矩脉动
            subplot(3,3,8);
            torque_ripple = obj.results.torque - mean(obj.results.torque);
            plot(time, torque_ripple, 'c-', 'LineWidth', 1.5);
            ylabel('转矩脉动 (N·m)');
            xlabel('时间 (s)');
            title('转矩脉动');
            grid on;
            
            % 性能指标
            subplot(3,3,9);
            obj.calculate_performance_metrics();
        end
        
        function calculate_performance_metrics(obj)
            % 计算性能指标
            time = obj.results.time;
            omega_actual = obj.results.omega_actual;
            omega_ref = obj.results.omega_ref;
            torque = obj.results.torque;
            
            % 稳态误差
            steady_state_error = mean(omega_ref(end-100:end) - omega_actual(end-100:end));
            
            % 转矩脉动
            torque_ripple = std(torque);
            
            % 响应时间 (达到90%稳态值)
            target_speed = 0.9 * omega_ref(end);
            rise_time_index = find(omega_actual >= target_speed, 1);
            if ~isempty(rise_time_index)
                rise_time = time(rise_time_index);
            else
                rise_time = inf;
            end
            
            % 显示性能指标
            metrics_text = sprintf(['性能指标:\n' ...
                                  '稳态误差: %.3f rad/s\n' ...
                                  '转矩脉动: %.3f N·m\n' ...
                                  '上升时间: %.3f s\n' ...
                                  '最大超调: %.1f%%'], ...
                                  steady_state_error, torque_ripple, rise_time, 0);
            
            text(0.1, 0.5, metrics_text, 'Units', 'normalized', ...
                 'FontSize', 10, 'VerticalAlignment', 'middle');
            axis off;
        end
    end
end

5. Simulink仿真模型生成

function generate_simulink_model()
    % 生成SRM控制的Simulink模型
    
    % 创建新模型
    model_name = 'SRM_Control_System';
    new_system(model_name);
    open_system(model_name);
    
    % 添加主要模块
    % 1. 速度参考生成
    add_block('simulink/Sources/Step', [model_name '/Speed_Reference']);
    set_param([model_name '/Speed_Reference'], 'Time', '0.02', 'Before', '0', 'After', '100');
    
    % 2. PID速度控制器
    add_block('simulink/Discrete/Discrete PID Controller', [model_name '/Speed_PID']);
    
    % 3. 电流控制器
    add_block('simulink/Discrete/Discrete PID Controller 2', [model_name '/Current_PID']);
    
    % 4. PWM生成
    add_block('simulink/Discrete/PWM Generator', [model_name '/PWM_Generator']);
    
    % 5. SRM电机模型
    add_block('simulink/User-Defined Functions/MATLAB Function', [model_name '/SRM_Model']);
    
    % 6. 示波器
    add_block('simulink/Sinks/Scope', [model_name '/Scope']);
    
    % 连接模块
    add_line(model_name, 'Speed_Reference/1', 'Speed_PID/1');
    add_line(model_name, 'Speed_PID/1', 'Current_PID/1');
    add_line(model_name, 'Current_PID/1', 'PWM_Generator/1');
    add_line(model_name, 'PWM_Generator/1', 'SRM_Model/1');
    add_line(model_name, 'SRM_Model/1', 'Scope/1');
    add_line(model_name, 'SRM_Model/2', 'Speed_PID/2'); % 速度反馈
    
    fprintf('Simulink模型已生成: %s\n', model_name);
end

6. 主运行脚本

% SRM控制系统仿真主脚本
function main_srm_simulation()
    % 创建SRM仿真系统
    srm_sim = SRM_Simulation();
    
    % 运行不同场景的仿真
    scenarios = {'startup', 'speed_change', 'load_change'};
    
    for i = 1:length(scenarios)
        fprintf('\n=== 运行场景: %s ===\n', scenarios{i});
        
        % 运行仿真
        srm_sim.run_simulation(scenarios{i});
        
        % 绘制结果
        figure(i);
        srm_sim.plot_simulation_results();
        
        % 保存结果
        saveas(gcf, sprintf('SRM_Simulation_%s.png', scenarios{i}));
    end
    
    % 生成Simulink模型
    generate_simulink_model();
    
    % 参数敏感性分析
    perform_sensitivity_analysis();
end

% 参数敏感性分析
function perform_sensitivity_analysis()
    fprintf('\n=== 参数敏感性分析 ===\n');
    
    % 测试不同参数对性能的影响
    param_names = {'Kp_speed', 'Ki_speed', 'Kp_current', 'Ki_current'};
    param_values = {[0.1, 0.5, 1.0], [0.05, 0.1, 0.2], [0.5, 1.0, 2.0], [0.2, 0.5, 1.0]};
    
    figure('Position', [100, 100, 1200, 800]);
    
    for i = 1:length(param_names)
        subplot(2,2,i);
        
        performance = [];
        for j = 1:length(param_values{i})
            % 创建新的仿真实例
            sim_temp = SRM_Simulation();
            
            % 修改参数
            switch param_names{i}
                case 'Kp_speed'
                    sim_temp.controller.Kp_speed = param_values{i}(j);
                case 'Ki_speed'
                    sim_temp.controller.Ki_speed = param_values{i}(j);
                case 'Kp_current'
                    sim_temp.controller.Kp_current = param_values{i}(j);
                case 'Ki_current'
                    sim_temp.controller.Ki_current = param_values{i}(j);
            end
            
            % 运行仿真并评估性能
            sim_temp.run_simulation('startup');
            performance(j) = std(sim_temp.results.omega_actual(end-100:end));
        end
        
        plot(param_values{i}, performance, 'o-', 'LineWidth', 2, 'MarkerSize', 8);
        xlabel(param_names{i});
        ylabel('速度标准差');
        title([param_names{i}, ' 敏感性分析']);
        grid on;
    end
end

% 运行主函数
main_srm_simulation();

参考代码 开关磁阻电机控制系统仿真与设计 www.3dddown.com/cna/64460.html

特性

这个SRM控制系统仿真框架提供:

  1. 精确的电机建模:非线性电感特性、饱和效应
  2. 多种控制策略:电压控制、电流斩波、PWM控制
  3. 完整的功率变换器:不对称半桥拓扑
  4. 先进的控制算法:自适应开关角度优化
  5. 全面的性能分析:转矩脉动、效率、动态响应
  6. 参数敏感性分析:控制器参数优化

应用领域

  • 电动汽车驱动系统
  • 工业自动化设备
  • 家电电机控制
  • 航空航天作动系统
  • 风力发电系统
posted @ 2025-12-15 09:36  小前端攻城狮  阅读(16)  评论(0)    收藏  举报