ArduSub程序学习(9)-电机控制

1.motors_output();

电机输出控制函数 motors_output();位于Ardusub.cpp/fast_loop函数中,转到类型定义查看具体函数(位于motors.cpp)。

void Sub::motors_output()
{
    // Motor detection mode controls the thrusters directly
    if (control_mode == MOTOR_DETECT){
        return;
    }
    // check if we are performing the motor test
    if (ap.motor_test) {
        verify_motor_test();
    } else {
        motors.set_interlock(true);
        motors.output();
    }
}
  • control_mode:当前控制模式,可能有不同的模式(比如普通操作模式、检测模式等)。在这段代码中,MOTOR_DETECT 是一种特定模式,专门用于电机检测。
  • ap.motor_test:一个布尔变量,用于表示是否处于电机测试模式。
  • motorsSub 类中的电机控制对象,用于实际控制电机输出。
  • verify_motor_test():一个函数,应该用于检查电机测试的状态和执行相关操作。
  • motors.set_interlock(true):激活电机的互锁机制,确保电机安全控制。
  • motors.output():将电机输出信号发送给实际电机进行控制。

 

  • 检查电机检测模式 (MOTOR_DETECT):

    • 如果当前的 control_modeMOTOR_DETECT,这意味着系统处于电机检测模式。在这种模式下,电机的正常输出被跳过,直接返回,不进行任何输出操作。
  • 检查是否处于电机测试模式:

    • 如果 ap.motor_test 为真,表示正在进行电机测试。在这种情况下,调用 verify_motor_test() 函数,检查电机测试状态并进行相应处理。
  • 正常的电机输出:

    • 如果不在电机测试模式,系统将激活电机的互锁机制,通过 motors.set_interlock(true) 确保电机安全启动。
    • 最后调用 motors.output(),将电机输出信号发送给电机进行实际控制。这意味着电机的输出将根据系统状态或控制命令进行调整。

2.output();

 位于AP_MotorsMulticopter.cpp中,电机控制模块,它负责根据当前飞行状态和传感器数据计算各电机的推力,并将推力转换为具体的电机控制信号(如 PWM 信号),最终输出给电机。

void AP_MotorsMulticopter::output()
{
   
    update_throttle_filter();

    update_lift_max_from_batt_voltage();

    output_logic();

    output_armed_stabilizing();

    thrust_compensation();

    output_to_motors();

    output_boost_throttle();

    output_rpyt();
};

 

该函数依次执行多个步骤,从滤波到输出电机控制信号。每个步骤的具体作用如下:

2.1 update_throttle_filter()
  • 更新油门滤波器: 这个函数用于对输入的油门值进行滤波,平滑油门控制信号。滤波后的油门值用于后续的推力计算,能够减少因为油门输入剧烈变化而导致的飞行器不稳定。
2.2 update_lift_max_from_batt_voltage()
  • 根据电池电压更新最大推力: 这个函数根据当前电池的电压来调整最大推力限制。随着电池电压的下降,电机的最大推力会相应降低,因此需要实时更新系统对推力的期望值,以避免超出电机或电池的能力。
2.3 output_logic()
  • 执行电机的起停逻辑: 这个函数运行电机的 "spool-up" 或 "spool-down" 逻辑,决定电机是应该加速到工作速度(启动)还是减速停止。这通常与飞行器是否武装(armed)或需要停机(disarmed)有关。
2.4 output_armed_stabilizing()
  • 计算推力输出: 这个函数计算当前状态下所需的推力输出,确保飞行器的稳定性。这包括根据姿态控制(roll、pitch、yaw)和总油门输入来分配推力,从而维持飞行器的稳定飞行状态。
2.5 thrust_compensation()
  • 应用推力补偿: 推力补偿用于修正由于框架或其他外部因素(例如悬挂负载、不对称设计等)对推力输出的影响。这个函数会根据飞行器的具体情况对每个电机的推力进行微调,以补偿这些偏差。
2.6 output_to_motors()
  • 将 rpy_thrust 转换为 PWM 信号: 在这个步骤中,飞行器的横滚(roll)、俯仰(pitch)、偏航(yaw)和总推力(thrust)值被转换为具体的 PWM 控制信号。PWM 信号是电机控制器实际接收并执行的指令。
2.7 output_boost_throttle()
  • 输出增压油门: 如果系统中有增压功能(如额外的推力器或涡轮增压装置),这个函数会计算并输出所需的增压油门值。
2.8 output_rpyt()
  • 输出原始的 roll/pitch/yaw/thrust 值: 最后一步,输出未经进一步处理的横滚、俯仰、偏航和推力值。这些值可以用于日志记录、调试,或者在某些特殊控制模式下直接应用。

3.output_armed_stabilizing();

位于AP_MotorsMatrix.cpp中,通过计算横滚、俯仰和偏航推力来分配给每个电机合适的推力输出,并根据最小和最大推力值对控制信号进行约束。

以bluerov2的6推进器为例,比如我现在要前进,通过计算每个电机对于俯仰,横滚,偏航的推力来分配每个电机,通过我保持前进的信号,分配到5电机和6电机不需要其他操作,只需要保持一定的推力保持机体的平衡就行,而3,4电机计算后的推力推动向前,1,2电机反向推力推动机体向前。

void AP_MotorsMatrix::output_armed_stabilizing()
{
    uint8_t i;                          // general purpose counter
    float   roll_thrust;                // roll thrust input value, +/- 1.0
    float   pitch_thrust;               // pitch thrust input value, +/- 1.0
    float   yaw_thrust;                 // yaw thrust input value, +/- 1.0
    float   throttle_thrust;            // throttle thrust input value, 0.0 - 1.0
    float   throttle_avg_max;           // throttle thrust average maximum value, 0.0 - 1.0
    float   throttle_thrust_max;        // throttle thrust maximum value, 0.0 - 1.0
    float   throttle_thrust_best_rpy;   // throttle providing maximum roll, pitch and yaw range without climbing
    float   rpy_scale = 1.0f;           // this is used to scale the roll, pitch and yaw to fit within the motor limits
    float   yaw_allowed = 1.0f;         // amount of yaw we can fit in
    float   thr_adj;                    // the difference between the pilot's desired throttle and throttle_thrust_best_rpy

    // apply voltage and air pressure compensation
    const float compensation_gain = get_compensation_gain(); // compensation for battery voltage and altitude
    roll_thrust = (_roll_in + _roll_in_ff) * compensation_gain;
    pitch_thrust = (_pitch_in + _pitch_in_ff) * compensation_gain;
    yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
    throttle_thrust = get_throttle() * compensation_gain;
    throttle_avg_max = _throttle_avg_max * compensation_gain;

    // If thrust boost is active then do not limit maximum thrust
    throttle_thrust_max = _thrust_boost_ratio + (1.0f - _thrust_boost_ratio) * _throttle_thrust_max * compensation_gain;

    // sanity check throttle is above zero and below current limited throttle
    if (throttle_thrust <= 0.0f) {
        throttle_thrust = 0.0f;
        limit.throttle_lower = true;
    }
    if (throttle_thrust >= throttle_thrust_max) {
        throttle_thrust = throttle_thrust_max;
        limit.throttle_upper = true;
    }

    // ensure that throttle_avg_max is between the input throttle and the maximum throttle
    throttle_avg_max = constrain_float(throttle_avg_max, throttle_thrust, throttle_thrust_max);

    // calculate the highest allowed average thrust that will provide maximum control range
    throttle_thrust_best_rpy = MIN(0.5f, throttle_avg_max);

    // calculate throttle that gives most possible room for yaw which is the lower of:
    //      1. 0.5f - (rpy_low+rpy_high)/2.0 - this would give the maximum possible margin above the highest motor and below the lowest
    //      2. the higher of:
    //            a) the pilot's throttle input
    //            b) the point _throttle_rpy_mix between the pilot's input throttle and hover-throttle
    //      Situation #2 ensure we never increase the throttle above hover throttle unless the pilot has commanded this.
    //      Situation #2b allows us to raise the throttle above what the pilot commanded but not so far that it would actually cause the copter to rise.
    //      We will choose #1 (the best throttle for yaw control) if that means reducing throttle to the motors (i.e. we favor reducing throttle *because* it provides better yaw control)
    //      We will choose #2 (a mix of pilot and hover throttle) only when the throttle is quite low.  We favor reducing throttle instead of better yaw control because the pilot has commanded it

    // Under the motor lost condition we remove the highest motor output from our calculations and let that motor go greater than 1.0
    // To ensure control and maximum righting performance Hex and Octo have some optimal settings that should be used
    // Y6               : MOT_YAW_HEADROOM = 350, ATC_RAT_RLL_IMAX = 1.0,   ATC_RAT_PIT_IMAX = 1.0,   ATC_RAT_YAW_IMAX = 0.5
    // Octo-Quad (x8) x : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.375, ATC_RAT_PIT_IMAX = 0.375, ATC_RAT_YAW_IMAX = 0.375
    // Octo-Quad (x8) + : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.75,  ATC_RAT_PIT_IMAX = 0.75,  ATC_RAT_YAW_IMAX = 0.375
    // Usable minimums below may result in attitude offsets when motors are lost. Hex aircraft are only marginal and must be handles with care
    // Hex              : MOT_YAW_HEADROOM = 0,   ATC_RAT_RLL_IMAX = 1.0,   ATC_RAT_PIT_IMAX = 1.0,   ATC_RAT_YAW_IMAX = 0.5
    // Octo-Quad (x8) x : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.25,  ATC_RAT_PIT_IMAX = 0.25,  ATC_RAT_YAW_IMAX = 0.25
    // Octo-Quad (x8) + : MOT_YAW_HEADROOM = 300, ATC_RAT_RLL_IMAX = 0.5,   ATC_RAT_PIT_IMAX = 0.5,   ATC_RAT_YAW_IMAX = 0.25
    // Quads cannot make use of motor loss handling because it doesn't have enough degrees of freedom.

    // calculate amount of yaw we can fit into the throttle range
    // this is always equal to or less than the requested yaw from the pilot or rate controller
    float rp_low = 1.0f;    // lowest thrust value
    float rp_high = -1.0f;  // highest thrust value
    for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
        if (motor_enabled[i]) {
            // calculate the thrust outputs for roll and pitch
            _thrust_rpyt_out[i] = roll_thrust * _roll_factor[i] + pitch_thrust * _pitch_factor[i];
            // record lowest roll + pitch command
            if (_thrust_rpyt_out[i] < rp_low) {
                rp_low = _thrust_rpyt_out[i];
            }
            // record highest roll + pitch command
            if (_thrust_rpyt_out[i] > rp_high && (!_thrust_boost || i != _motor_lost_index)) {
                rp_high = _thrust_rpyt_out[i];
            }

            // Check the maximum yaw control that can be used on this channel
            // Exclude any lost motors if thrust boost is enabled
            if (!is_zero(_yaw_factor[i]) && (!_thrust_boost || i != _motor_lost_index)){
                if (is_positive(yaw_thrust * _yaw_factor[i])) {
                    yaw_allowed = MIN(yaw_allowed, fabsf(MAX(1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[i]), 0.0f)/_yaw_factor[i]));
                } else {
                    yaw_allowed = MIN(yaw_allowed, fabsf(MAX(throttle_thrust_best_rpy + _thrust_rpyt_out[i], 0.0f)/_yaw_factor[i]));
                }
            }
        }
    }

    // calculate the maximum yaw control that can be used
    // todo: make _yaw_headroom 0 to 1
    float yaw_allowed_min = (float)_yaw_headroom / 1000.0f;

    // increase yaw headroom to 50% if thrust boost enabled
    yaw_allowed_min = _thrust_boost_ratio * 0.5f + (1.0f - _thrust_boost_ratio) * yaw_allowed_min;

    // Let yaw access minimum amount of head room
    yaw_allowed = MAX(yaw_allowed, yaw_allowed_min);

    // Include the lost motor scaled by _thrust_boost_ratio to smoothly transition this motor in and out of the calculation
    if (_thrust_boost && motor_enabled[_motor_lost_index]) {
        // record highest roll + pitch command
        if (_thrust_rpyt_out[_motor_lost_index] > rp_high) {
            rp_high = _thrust_boost_ratio * rp_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index];
        }

        // Check the maximum yaw control that can be used on this channel
        // Exclude any lost motors if thrust boost is enabled
        if (!is_zero(_yaw_factor[_motor_lost_index])){
            if (is_positive(yaw_thrust * _yaw_factor[_motor_lost_index])) {
                yaw_allowed = _thrust_boost_ratio * yaw_allowed + (1.0f - _thrust_boost_ratio) * MIN(yaw_allowed, fabsf(MAX(1.0f - (throttle_thrust_best_rpy + _thrust_rpyt_out[_motor_lost_index]), 0.0f)/_yaw_factor[_motor_lost_index]));
            } else {
                yaw_allowed = _thrust_boost_ratio * yaw_allowed + (1.0f - _thrust_boost_ratio) * MIN(yaw_allowed, fabsf(MAX(throttle_thrust_best_rpy + _thrust_rpyt_out[_motor_lost_index], 0.0f)/_yaw_factor[_motor_lost_index]));
            }
        }
    }

    if (fabsf(yaw_thrust) > yaw_allowed) {
        // not all commanded yaw can be used
        yaw_thrust = constrain_float(yaw_thrust, -yaw_allowed, yaw_allowed);
        limit.yaw = true;
    }

    // add yaw control to thrust outputs
    float rpy_low = 1.0f;   // lowest thrust value
    float rpy_high = -1.0f; // highest thrust value
    for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
        if (motor_enabled[i]) {
            _thrust_rpyt_out[i] = _thrust_rpyt_out[i] + yaw_thrust * _yaw_factor[i];

            // record lowest roll + pitch + yaw command
            if (_thrust_rpyt_out[i] < rpy_low) {
                rpy_low = _thrust_rpyt_out[i];
            }
            // record highest roll + pitch + yaw command
            // Exclude any lost motors if thrust boost is enabled
            if (_thrust_rpyt_out[i] > rpy_high && (!_thrust_boost || i != _motor_lost_index)) {
                rpy_high = _thrust_rpyt_out[i];
            }
        }
    }
    // Include the lost motor scaled by _thrust_boost_ratio to smoothly transition this motor in and out of the calculation
    if (_thrust_boost) {
        // record highest roll + pitch + yaw command
        if (_thrust_rpyt_out[_motor_lost_index] > rpy_high && motor_enabled[_motor_lost_index]) {
            rpy_high = _thrust_boost_ratio * rpy_high + (1.0f - _thrust_boost_ratio) * _thrust_rpyt_out[_motor_lost_index];
        }
    }

    // calculate any scaling needed to make the combined thrust outputs fit within the output range
    if (rpy_high - rpy_low > 1.0f) {
        rpy_scale = 1.0f / (rpy_high - rpy_low);
    }
    if (throttle_avg_max + rpy_low < 0) {
        rpy_scale = MIN(rpy_scale, -throttle_avg_max / rpy_low);
    }

    // calculate how close the motors can come to the desired throttle
    rpy_high *= rpy_scale;
    rpy_low *= rpy_scale;
    throttle_thrust_best_rpy = -rpy_low;
    thr_adj = throttle_thrust - throttle_thrust_best_rpy;
    if (rpy_scale < 1.0f) {
        // Full range is being used by roll, pitch, and yaw.
        limit.roll = true;
        limit.pitch = true;
        limit.yaw = true;
        if (thr_adj > 0.0f) {
            limit.throttle_upper = true;
        }
        thr_adj = 0.0f;
    } else {
        if (thr_adj < 0.0f) {
            // Throttle can't be reduced to desired value
            // todo: add lower limit flag and ensure it is handled correctly in altitude controller
            thr_adj = 0.0f;
        } else if (thr_adj > 1.0f - (throttle_thrust_best_rpy + rpy_high)) {
            // Throttle can't be increased to desired value
            thr_adj = 1.0f - (throttle_thrust_best_rpy + rpy_high);
            limit.throttle_upper = true;
        }
    }

    // add scaled roll, pitch, constrained yaw and throttle for each motor
    const float throttle_thrust_best_plus_adj = throttle_thrust_best_rpy + thr_adj;
    for (i = 0; i < AP_MOTORS_MAX_NUM_MOTORS; i++) {
        if (motor_enabled[i]) {
            _thrust_rpyt_out[i] = (throttle_thrust_best_plus_adj * _throttle_factor[i]) + (rpy_scale * _thrust_rpyt_out[i]);
        }
    }

    // determine throttle thrust for harmonic notch
    // compensation_gain can never be zero
    _throttle_out = throttle_thrust_best_plus_adj / compensation_gain;

    // check for failed motor
    check_for_failed_motor(throttle_thrust_best_plus_adj);
}
3.1 推力补偿与初始计算:
  • 函数一开始会根据电池电压和空气压力计算补偿增益 (compensation_gain),并将该增益应用于 roll、pitch、yaw 和油门的输入值。这样做是为了应对电压下降或气压变化带来的推力变化。
  • 接着,函数计算最大油门推力 throttle_thrust_max,如果启用了推力提升(boost),则会相应调整最大推力限制。
3.2 推力限幅:
  • 检查油门推力 throttle_thrust 是否在允许的范围内,如果超出范围,则将其限制在 [0.0, throttle_thrust_max] 之间。
  • 然后,函数根据 roll_thrustpitch_thrust 计算每个电机的推力输出,并找到 roll 和 pitch 计算的最低和最高推力值 (rp_lowrp_high)。
3.3 偏航控制调整:
  • 函数计算在当前油门推力下可以容纳的最大偏航量 yaw_allowed。如果飞行器的推力已经接近上限,允许的偏航量将会减少,确保不超出电机的能力。
  • 如果偏航控制超过了允许的范围,则将其限制在 yaw_allowed 范围内,并标记偏航已被限制。
3.4 综合推力输出:
  • 将经过缩放后的 roll、pitch 和 yaw 的推力值加上油门推力,为每个电机计算最终的推力输出。如果 roll、pitch 和 yaw 的总和超出了电机能力范围,函数会对其进行缩放以保证推力输出在安全范围内。
  • 如果某个电机失效(如遇到失效电机模式),会对其推力进行特殊处理,以保证其余电机可以平衡飞行器。
3.5 最终推力计算:
  • 最后,函数将计算出的推力输出应用到电机上,并检测是否有电机失效。如果发现失效电机,系统将进入相关的处理流程。

 4.setup_motors

也是位于AP_MotorsMatrix.cpp中,这段代码太长了,这里就不给源码了。

这个函数最主要的内容就是配置电机,包括每个电机对于不同运动的影响程度(推力分配)。

4.1函数刚开始,首先就是把最初的所有电机配置全部移除,方便后续进行更改。这里的AP_MOTORS_MAX_NUM_MOTORS为最大的电机数,于AP_Motors_Class.h中定义为12。

4.2然后进入一个switch()函数中进行具体的配置内容,首先判断是属于哪一种frame_class的架构

 enum motor_frame_class {
        MOTOR_FRAME_UNDEFINED = 0,
        MOTOR_FRAME_QUAD = 1,
        MOTOR_FRAME_HEXA = 2,
        MOTOR_FRAME_OCTA = 3,
        MOTOR_FRAME_OCTAQUAD = 4,
        MOTOR_FRAME_Y6 = 5,
        MOTOR_FRAME_HELI = 6,
        MOTOR_FRAME_TRI = 7,
        MOTOR_FRAME_SINGLE = 8,
        MOTOR_FRAME_COAX = 9,
        MOTOR_FRAME_TAILSITTER = 10,
        MOTOR_FRAME_HELI_DUAL = 11,
        MOTOR_FRAME_DODECAHEXA = 12,
        MOTOR_FRAME_HELI_QUAD = 13,
        MOTOR_FRAME_DECA = 14,
        MOTOR_FRAME_SCRIPTING_MATRIX = 15,
        MOTOR_FRAME_6DOF_SCRIPTING = 16,
    };
  • MOTOR_FRAME_UNDEFINED (0):未定义的电机框架类型。

  • MOTOR_FRAME_QUAD (1):四旋翼框架,通常有四个电机。

  • MOTOR_FRAME_HEXA (2):六旋翼框架,有六个电机。

  • MOTOR_FRAME_OCTA (3):八旋翼框架,有八个电机。

  • MOTOR_FRAME_OCTAQUAD (4):八电机四旋翼框架,可能用于特定的配置。

  • MOTOR_FRAME_Y6 (5):Y6 型框架,通常是六旋翼的一种配置。

  • MOTOR_FRAME_HELI (6):直升机框架,适用于传统的直升机配置。

  • MOTOR_FRAME_TRI (7):三旋翼框架,通常有三个电机。

  • MOTOR_FRAME_SINGLE (8):单电机框架,适用于简单的飞行器。

  • MOTOR_FRAME_COAX (9):共轴框架,通常有两个电机共轴旋转。

  • MOTOR_FRAME_TAILSITTER (10):尾坐式飞行器,具有固定翼和垂直起降的能力。

  • MOTOR_FRAME_HELI_DUAL (11):双直升机框架,可能用于特定的双旋翼设计。

  • MOTOR_FRAME_DODECAHEXA (12):十二电机六旋翼框架,可能用于高承载需求的飞行器。

  • MOTOR_FRAME_HELI_QUAD (13):四旋翼直升机框架,结合了四旋翼和直升机的特性。

  • MOTOR_FRAME_DECA (14):十电机框架,适用于需要高稳定性或承载能力的设计。

  • MOTOR_FRAME_SCRIPTING_MATRIX (15):脚本矩阵框架,可能用于用户定义的电机配置。

  • MOTOR_FRAME_6DOF_SCRIPTING (16):六自由度脚本框架,可能用于更复杂的运动控制。

4.3 motor_frame_type,选择用于表示不同的电机框架类型。

 enum motor_frame_type {
        MOTOR_FRAME_TYPE_PLUS = 0,
        MOTOR_FRAME_TYPE_X = 1,
        MOTOR_FRAME_TYPE_V = 2,
        MOTOR_FRAME_TYPE_H = 3,
        MOTOR_FRAME_TYPE_VTAIL = 4,
        MOTOR_FRAME_TYPE_ATAIL = 5,
        MOTOR_FRAME_TYPE_PLUSREV = 6, // plus with reversed motor direction
        MOTOR_FRAME_TYPE_Y6B = 10,
        MOTOR_FRAME_TYPE_Y6F = 11, // for FireFlyY6
        MOTOR_FRAME_TYPE_BF_X = 12, // X frame, betaflight ordering
        MOTOR_FRAME_TYPE_DJI_X = 13, // X frame, DJI ordering
        MOTOR_FRAME_TYPE_CW_X = 14, // X frame, clockwise ordering
        MOTOR_FRAME_TYPE_I = 15, // (sideways H) octo only
        MOTOR_FRAME_TYPE_NYT_PLUS = 16, // plus frame, no differential torque for yaw
        MOTOR_FRAME_TYPE_NYT_X = 17, // X frame, no differential torque for yaw
        MOTOR_FRAME_TYPE_BF_X_REV = 18, // X frame, betaflight ordering, reversed motors
    };
  • MOTOR_FRAME_TYPE_PLUS (0):加号框架,通常是四旋翼配置。

  • MOTOR_FRAME_TYPE_X (1):X型框架,另一种常见的四旋翼配置。

  • MOTOR_FRAME_TYPE_V (2):V型框架,适用于特定的飞行器设计。

  • MOTOR_FRAME_TYPE_H (3):H型框架,通常用于具有平行电机的配置。

  • MOTOR_FRAME_TYPE_VTAIL (4):V尾框架,具有特殊的尾部电机配置,适用于VTOL(垂直起降)飞行器。

  • MOTOR_FRAME_TYPE_ATAIL (5):A尾框架,与V尾框架相似,但电机方向相反。

  • MOTOR_FRAME_TYPE_PLUSREV (6):加号框架,电机方向反转的版本。

  • MOTOR_FRAME_TYPE_Y6B (10):Y6型框架的一种变体。

  • MOTOR_FRAME_TYPE_Y6F (11):专为 FireFly Y6 设计的 Y6型框架。

  • MOTOR_FRAME_TYPE_BF_X (12):按照 Betaflight 顺序的 X型框架。

  • MOTOR_FRAME_TYPE_DJI_X (13):按照 DJI 顺序的 X型框架。

  • MOTOR_FRAME_TYPE_CW_X (14):顺时针 X型框架。

  • MOTOR_FRAME_TYPE_I (15):侧向 H型框架,仅适用于八旋翼。

  • MOTOR_FRAME_TYPE_NYT_PLUS (16):加号框架,适用于没有差动扭矩用于偏航控制的情况。

  • MOTOR_FRAME_TYPE_NYT_X (17):X型框架,适用于没有差动扭矩用于偏航控制的情况。

  • MOTOR_FRAME_TYPE_BF_X_REV (18):按照 Betaflight 顺序的 X型框架,电机方向反转。

4.4 配置电机:调用 add_motor 函数来添加电机

case MOTOR_FRAME_TYPE_PLUS:
                    _frame_type_string = "PLUS";
                    add_motor(AP_MOTORS_MOT_1,  90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 2);
                    add_motor(AP_MOTORS_MOT_2, -90, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 4);
                    add_motor(AP_MOTORS_MOT_3,   0, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  1);
                    add_motor(AP_MOTORS_MOT_4, 180, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  3);
                    break;
                case MOTOR_FRAME_TYPE_X:
                    _frame_type_string = "X";
                    add_motor(AP_MOTORS_MOT_1,   45, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 1);
                    add_motor(AP_MOTORS_MOT_2, -135, AP_MOTORS_MATRIX_YAW_FACTOR_CCW, 3);
                    add_motor(AP_MOTORS_MOT_3,  -45, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  4);
                    add_motor(AP_MOTORS_MOT_4,  135, AP_MOTORS_MATRIX_YAW_FACTOR_CW,  2);
                    break;

该函数的参数通常包括:

  • 电机编号(如 AP_MOTORS_MOT_1
  • 旋转角度(如 90-90 等)
  • 方向因子(如 AP_MOTORS_MATRIX_YAW_FACTOR_CWAP_MOTORS_MATRIX_YAW_FACTOR_CCW
  • 电机的索引位置(如 1234

 

评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

仗剑走代码

“您的支持是我创作的动力”

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值