1. 一些概念
- AC_CustomControl允许您以系统的方式在ArduPilot中实现并轻松运行自己的控制算法。
- 仅局限与角速度控制环;
- 设置一个RC通道作为控制器切换,如RC6_OPTION = 109。
- CC_AXIS_MASK 设置roll、pitch、yaw哪些轴参与CustomControl
- 控制器切换时,滤波器、积分器会进行复位
- 从自定义控制器切换到主控制器时的无障碍传输
- 地面和飞行中的线轴状态分离,以避免在使用自定义控制器武装和起飞期间积累
- 前端-后端分离,允许以非常小的开销添加新控制器
- 编译自定义控制器在编译固件时要加入参数:
./waf configure --board=CubeOrange copter --enable-custom-controller
注意:在SITL中默认开启了CustomControl,所以不需要配置。
- 允许添加新的自定义控制器参数
- 自定义控制器参数在GCS中以 “CC_” 为前缀。
- custom controller 在SITL中可用,可在SITL中先测试;
- …
2. 参数
- 前端参数
- CC_TYPE
自定义控制器后端类型,0时关闭功能;
0 None,1 Empty,2 PID,3 ADRC(新添加) - CC_AXIS_MASK
设置roll、pitch、yaw哪些轴参与CustomControl
- CC_TYPE
3. 原理解析
- custom controller update function 什么时候被调用的?
在 main rate controller 调用之后
在motor output 之前
这样电机混控器 motor mixer 输入量:_roll_in
,_pitch_in
,_yaw_in
就可以被custom controller 的输出所覆盖; - custom controller的期望值来源
custom controller 和main rate controller 使用相同的期望值,都来源于AC_AttitudeControl library ,更具的说来源于 - 运行自定义控制器后,混合器输入通过“set_roll”、“set_pitch”和“set_yaw”功能发送到电机库。
- 控制器切换回主控制器时会做哪些
当从自定义控制器切换到主控制器时,会重置主控制器的以下参数:目标值、误差、d项滤波器并正确设置每个轴积分器。一避免由控制量不连续导致的飞机突然的机动。为了在控制器之间实现平稳过渡,当切换出重置主控制器所有三个轴的自定义控制器时,会调用主控制器重置功能。
相关函数:reset_main_atti_controller
举例代码:
_atti_control->get_rate_roll_pid().reset_filter();
_atti_control->get_rate_roll_pid().set_integrator(_atti_control->rate_bf_targets().x - gyro_latest.x, _motors->get_roll());
4. 使用步骤
- 1)添加自定义控制算法代码进ardupilot中,编译固件:
./waf configure --board=CubeOrange copter --enable-custom-controller
- 2)参数设置
CC_TYPE = 2或其他,根据具体情况而定
CC_AXIS_MASK = 7或其他,根据具体情况而定
RC6_OPTION = 109 - 3)重启
- 4)设置自定义控制算法的其他参数,以CC3为前缀的参数们
- 5)起飞,悬停,遥控器切换至自定义控制器,观察响应,调整参数…
5. 开发文档、使用文档
- Ardupilot\libraries\AC_CustomControl\README.md
- Adding Custom Attitude Controller to Copter
- 如何添加自定义控制器?
- 假设添加的是第5个custom controller
- 1)复制 AC_CustomControl_Empty.cpp 和 AC_CustomControl_Empty.h 文件到目录Library/AC_CustomControl中,并重命名,如AC_CustomControl_ADRC.cpp、AC_CustomControl_ADRC.h;
将 AC_CustomControl_ADRC.cpp、AC_CustomControl_ADRC.h 中所有的
AC_CustomControl_Empty 替换为 AC_CustomControl_ADRC。
将.cpp .h中所有的宏定义AP_CUSTOMCONTROL_EMPTY_ENABLED替换为 AP_CUSTOMCONTROL_ADRC_ENABLED
将实现自定义算法ADRC的头文件包含进AC_CustomControl_ADRC.h中:
#include "AC_ADRC/AC_ADRC.h"
- 2)在AC_CustomCon