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/libraries/AC_CustomControl/AC_CustomControl.cpp
Views: 1798
#include <AP_HAL/AP_HAL.h>12#include "AC_CustomControl.h"34#if AP_CUSTOMCONTROL_ENABLED56#include "AC_CustomControl_Backend.h"7// #include "AC_CustomControl_Empty.h"8#include "AC_CustomControl_PID.h"9#include <GCS_MAVLink/GCS.h>10#include <AP_Logger/AP_Logger.h>1112// table of user settable parameters13const AP_Param::GroupInfo AC_CustomControl::var_info[] = {14// @Param: _TYPE15// @DisplayName: Custom control type16// @Description: Custom control type to be used17// @Values: 0:None, 1:Empty, 2:PID18// @RebootRequired: True19// @User: Advanced20AP_GROUPINFO_FLAGS("_TYPE", 1, AC_CustomControl, _controller_type, 0, AP_PARAM_FLAG_ENABLE),2122// @Param: _AXIS_MASK23// @DisplayName: Custom Controller bitmask24// @Description: Custom Controller bitmask to chose which axis to run25// @Bitmask: 0:Roll, 1:Pitch, 2:Yaw26// @User: Advanced27AP_GROUPINFO("_AXIS_MASK", 2, AC_CustomControl, _custom_controller_mask, 0),2829// parameters for empty controller. only used as a template, no need for param table30// AP_SUBGROUPVARPTR(_backend, "1_", 6, AC_CustomControl, _backend_var_info[0]),3132// parameters for PID controller33AP_SUBGROUPVARPTR(_backend, "2_", 7, AC_CustomControl, _backend_var_info[1]),3435AP_GROUPEND36};3738const struct AP_Param::GroupInfo *AC_CustomControl::_backend_var_info[CUSTOMCONTROL_MAX_TYPES];3940AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :41_dt(dt),42_ahrs(ahrs),43_att_control(att_control),44_motors(motors)45{46AP_Param::setup_object_defaults(this, var_info);47}4849void AC_CustomControl::init(void)50{51switch (CustomControlType(_controller_type))52{53case CustomControlType::CONT_NONE:54break;55case CustomControlType::CONT_EMPTY: // This is template backend. Don't initialize it.56// This is template backend. Don't initialize it.57// _backend = NEW_NOTHROW AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt);58// _backend_var_info[get_type()] = AC_CustomControl_Empty::var_info;59break;60case CustomControlType::CONT_PID:61_backend = NEW_NOTHROW AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt);62_backend_var_info[get_type()] = AC_CustomControl_PID::var_info;63break;64default:65return;66}6768if (_backend && _backend_var_info[get_type()]) {69AP_Param::load_object_from_eeprom(_backend, _backend_var_info[get_type()]);70}71}7273// run custom controller if it is activated by RC switch and appropriate type is selected74void AC_CustomControl::update(void)75{76if (is_safe_to_run()) {77Vector3f motor_out_rpy;7879motor_out_rpy = _backend->update();8081motor_set(motor_out_rpy);82}83}8485// choose which axis to apply custom controller output86void AC_CustomControl::motor_set(Vector3f rpy) {87if (_custom_controller_mask & (uint8_t)CustomControlOption::ROLL) {88_motors->set_roll(rpy.x);89_att_control->get_rate_roll_pid().set_integrator(0.0);90}91if (_custom_controller_mask & (uint8_t)CustomControlOption::PITCH) {92_motors->set_pitch(rpy.y);93_att_control->get_rate_pitch_pid().set_integrator(0.0);94}95if (_custom_controller_mask & (uint8_t)CustomControlOption::YAW) {96_motors->set_yaw(rpy.z);97_att_control->get_rate_yaw_pid().set_integrator(0.0);98}99}100101// move main controller's target to current states, reset filters,102// and move integrator to motor output103// to allow smooth transition to the primary controller104void AC_CustomControl::reset_main_att_controller(void)105{106// reset attitude and rate target, if feedforward is enabled107if (_att_control->get_bf_feedforward()) {108_att_control->relax_attitude_controllers();109}110111_att_control->get_rate_roll_pid().set_integrator(0.0);112_att_control->get_rate_pitch_pid().set_integrator(0.0);113_att_control->get_rate_yaw_pid().set_integrator(0.0);114}115116void AC_CustomControl::set_custom_controller(bool enabled)117{118// double logging switch makes the state change very clear in the log119log_switch();120121_custom_controller_active = false;122123// don't allow accidental main controller reset without active custom controller124if (_controller_type == CustomControlType::CONT_NONE) {125GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is not enabled");126return;127}128129// controller type is out of range130if (_controller_type > CUSTOMCONTROL_MAX_TYPES) {131GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller type is out of range");132return;133}134135// backend is not created136if (_backend == nullptr) {137GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller");138return;139}140141if (_custom_controller_mask == 0 && enabled) {142GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Axis mask is not set");143return;144}145146// reset main controller147if (!enabled) {148GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is OFF");149// don't reset if the empty backend is selected150if (_controller_type > CustomControlType::CONT_EMPTY) {151reset_main_att_controller();152}153}154155if (enabled && _controller_type > CustomControlType::CONT_NONE) {156// reset custom controller filter, integrator etc.157_backend->reset();158GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is ON");159}160161_custom_controller_active = enabled;162163// log successful switch164log_switch();165}166167// check that RC switch is on, backend is not changed mid flight and controller type is selected168bool AC_CustomControl::is_safe_to_run(void) {169if (_custom_controller_active && (_controller_type > CustomControlType::CONT_NONE)170&& (_controller_type <= CUSTOMCONTROL_MAX_TYPES) && _backend != nullptr)171{172return true;173}174175return false;176}177178// log when the custom controller is switch into179void AC_CustomControl::log_switch(void) {180AP::logger().Write("CC", "TimeUS,Type,Act","QBB",181AP_HAL::micros64(),182_controller_type,183_custom_controller_active);184}185186void AC_CustomControl::set_notch_sample_rate(float sample_rate)187{188#if AP_FILTER_ENABLED189if (_backend != nullptr) {190_backend->set_notch_sample_rate(sample_rate);191}192#endif193}194195#endif // AP_CUSTOMCONTROL_ENABLED196197198