PIXHAWK(ardupilot4.52)单ic通道输出pwm

可以看到飞控具有16个ic输出通道,理论上每一个通道都可以单独输出pwm,那么怎样才能在固件中让每个通道都单独输出pwm呢?

1、

手动模式下油门控制可以直观的控制pwm输出,

在void ModeManual::update()中可以看到g2.motors.set_throttle(desired_throttle); 就是油门处理函数。可以根据这个函数寻址找到void AP_MotorsUGV::set_throttle(float throttle)函数

cpp 复制代码
//libraries/AR_Motors/AP_MotorsUGV.cpp 
void AP_MotorsUGV::set_throttle(float throttle)
{
    // only allow setting throttle if armed
    if (!hal.util->get_soft_armed()) {
        return;
    }
    // check throttle is between -_throttle_max and  +_throttle_max
    _throttle = constrain_float(throttle, -_throttle_max, _throttle_max);
}

在这个函数中可以看到形参desired_throttle最终是递给了_throttle这个参数。接下来就是在该文件下找哪里使用了_throttle这个参数。

cpp 复制代码
void AP_MotorsUGV::output(bool armed, float ground_speed, float dt)
{
    // soft-armed overrides passed in armed status 以武装状态通过软武装覆盖
    if (!hal.util->get_soft_armed()) {
        armed = false;
        _throttle = 0.0f;
    }

    // clear limit flags
    // output_ methods are responsible for setting them to true if required on each iteration
    //清除限制标志
    //output_方法负责在每次迭代中根据需要将其设置为true
    limit.steer_left = limit.steer_right = limit.throttle_lower = limit.throttle_upper = false;

    // sanity check parameters 健全性检查参数
    sanity_check_parameters();

    // slew limit throttle 回转限制节流阀
    slew_limit_throttle(dt);

    // output for regular steering/throttle style frames 常规转向/油门式车架的输出
    output_regular(armed, ground_speed, _steering, _throttle);

    // output for skid steering style frames 滑移转向式车架的输出
    output_skid_steering(armed, _steering, _throttle, dt);

    // output for omni frames 全帧输出
    output_omni(armed, _steering, _throttle, _lateral);

    // output to sails 输出到帆
    output_sail();

    // send values to the PWM timers for output 将值发送到PWM定时器进行输出
    SRV_Channels::calc_pwm(); //计算所有通道的PWM
    SRV_Channels::cork();
    SRV_Channels::output_ch_all(); //控制pwm输出
    SRV_Channels::push();
}

搜索查找后可以找到void AP_MotorsUGV::output(bool armed, float ground_speed, float dt)这个函数,看名称可以判断为输出函数。_throttle在这个函数中使用了,但是最终都汇聚在SRV_Channels::output_ch_all();函数中,这个就是控制pwm输出函数。

继续寻址。找到SRV_Channels::output_ch_all()的定义。

cpp 复制代码
//libraries/SRV Channel/SRV Channel_aux.cpp 
void SRV_Channels::output_ch_all(void)
{
    uint8_t max_chan = NUM_SERVO_CHANNELS;
#if NUM_SERVO_CHANNELS >= 17
    if (_singleton != nullptr && _singleton->enable_32_channels.get() <= 0) {
        max_chan = 16;
    }
#endif
    for (uint8_t i = 0; i < max_chan; i++) {

        channels[i].output_ch();
    }
}

在函数的末尾可以看到channelsi.output_ch();这个函数,这个函数还不能直接输出定值的pwm,继续寻址。

cpp 复制代码
//libraries/SRV Channel/SRV Channel_aux.cpp 
void SRV_Channel::output_ch(void)
{
#ifndef HAL_BUILD_AP_PERIPH
    int8_t passthrough_from = -1;
    bool passthrough_mapped = false;

    // take care of special function cases 照顾特殊功能例
    switch(function.get())
    {
    case k_manual:              // manual
        passthrough_from = ch_num;
        break;
    case k_rcin1 ... k_rcin16: // rc pass-thru
        passthrough_from = int8_t((int16_t)function - k_rcin1);
        break;
    case k_rcin1_mapped ... k_rcin16_mapped:
        passthrough_from = int8_t((int16_t)function - k_rcin1_mapped);
        passthrough_mapped = true;
        break;
    }
    if (passthrough_from != -1) {
        // we are doing passthrough from input to output for this channel 我们正在为这个通道进行从输入到输出的直通
        RC_Channel *c = rc().channel(passthrough_from);
        if (c) {
            if (SRV_Channels::passthrough_disabled()) {
                output_pwm = c->get_radio_trim();
            } else {
                // non-mapped rc passthrough 非映射rc透传
                int16_t radio_in = c->get_radio_in();
                if (passthrough_mapped) {
                    if (rc().has_valid_input()) {
                        switch (c->get_type()) {
                        case RC_Channel::ControlType::ANGLE:
                            radio_in = pwm_from_angle(c->norm_input_dz() * 4500);
                            break;
                        case RC_Channel::ControlType::RANGE:
                            // convert RC normalised input from -1 to +1 range to 0 to +1 and output as range
                            radio_in = pwm_from_range((c->norm_input_ignore_trim() + 1.0) * 0.5 * 4500);
                            break;
                        }
                    } else {
                        // no valid input.  If we are in radio
                        // failsafe then go to trim values (if
                        // configured for this channel).  Otherwise
                        // use the last-good value
                        if ( ((1U<<passthrough_from) & SRV_Channels::get_rc_fs_mask()) && rc().in_rc_failsafe()) {
                            radio_in = pwm_from_angle(0);
                        } else {
                            radio_in = previous_radio_in;
                        }
                    }
                }
                if (!ign_small_rcin_changes) {
                    output_pwm = radio_in;
                    previous_radio_in = radio_in;
                } else {
                    // check if rc input value has changed by more than the deadzone
                    if (abs(radio_in - previous_radio_in) > c->get_dead_zone()) {
                        output_pwm = radio_in;
                        ign_small_rcin_changes = false;
                    }
                }
            }
        }
    }
#endif // HAL_BUILD_AP_PERIPH
    if (!(SRV_Channels::disabled_mask & (1U<<ch_num))) {
 //       hal.rcout->write(ch_num, output_pwm);//原版

        hal.rcout->write(ch_num, 900+ch_num*70);//实验测试

    }
}

该函数下,前面的都是验证每个通道分别需要多少的pwm输出,函数的最后才是控制单独通道的单独输出。

cpp 复制代码
 hal.rcout->write(ch_num, output_pwm);

其中ch_num即对应通道,output_pwm即需要输出的pwm,在这里修改代码测试一下:

cpp 复制代码
 hal.rcout->write(ch_num, 900+ch_num*70);

修改后,理论上第一个通道输出900,然后后面的通道逐个递增70。

编译完成后下载到飞控中查看ic通道输出。

可以看到ic通道确实是根据设定输出,但是只有前8个通道输出,后面8个却没有输出,这是为啥?

相关推荐
红尘散仙28 分钟前
我把终端小说阅读器接上了 AI Agent:TRNovel 现在能用 skill 生成书源了
人工智能·后端·rust
卷毛的技术笔记2 小时前
告别硬编码!Spring AI Alibaba 实现 AI Agent 智能工具调用(Tool Calling)
java·人工智能·后端·python·spring·ai编程
会编程的土豆2 小时前
Go 语言反射(Reflection)详解
开发语言·后端·golang
喵个咪2 小时前
GoWind Toolkit Go后端代码生成 完整全流程实战
后端·go·orm
basketball6163 小时前
Go 语言从入门到进阶:4. 数组和MAP使用方法总结
开发语言·后端·golang
qq_2518364573 小时前
SpringBoot+Vue 共享电池柜管理系统 完整实现 前后端分离项目实战 完整代码
vue.js·spring boot·后端
zhangxingchao3 小时前
AI 大模型核心六:量化、Workflow 与 Agent、多轮 RAG
前端·人工智能·后端
IT_陈寒4 小时前
Vite打包时遇到的坑,原来问题出在这里
前端·人工智能·后端
ayqy贾杰5 小时前
基层管理的三板斧,在AI时代行不通了
前端·后端·团队管理
Apifox5 小时前
Apifox 5 月更新|Postman 导入优化、Runner 支持非 root 运行、请求代码自动带鉴权
前端·后端·安全