Path: blob/master/libraries/AC_CustomControl/AC_CustomControl.cpp
9326 views
#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>11#include <AP_Scheduler/AP_Scheduler.h>1213// table of user settable parameters14const AP_Param::GroupInfo AC_CustomControl::var_info[] = {15// @Param: _TYPE16// @DisplayName: Custom control type17// @Description: Custom control type to be used18// @Values: 0:None, 1:Empty, 2:PID19// @RebootRequired: True20// @User: Advanced21AP_GROUPINFO_FLAGS("_TYPE", 1, AC_CustomControl, _controller_type, 0, AP_PARAM_FLAG_ENABLE),2223// @Param: _AXIS_MASK24// @DisplayName: Custom Controller bitmask25// @Description: Custom Controller bitmask to chose which axis to run26// @Bitmask: 0:Roll, 1:Pitch, 2:Yaw27// @User: Advanced28AP_GROUPINFO("_AXIS_MASK", 2, AC_CustomControl, _custom_controller_mask, 0),2930// parameters for empty controller. only used as a template, no need for param table31// AP_SUBGROUPVARPTR(_backend, "1_", 6, AC_CustomControl, _backend_var_info[0]),3233// parameters for PID controller34AP_SUBGROUPVARPTR(_backend, "2_", 7, AC_CustomControl, _backend_var_info[1]),3536AP_GROUPEND37};3839const struct AP_Param::GroupInfo *AC_CustomControl::_backend_var_info[CUSTOMCONTROL_MAX_TYPES];4041AC_CustomControl::AC_CustomControl(AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors) :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{51_dt = AP::scheduler().get_loop_period_s();5253switch (CustomControlType(_controller_type))54{55case CustomControlType::CONT_NONE:56break;57case CustomControlType::CONT_EMPTY: // This is template backend. Don't initialize it.58// This is template backend. Don't initialize it.59// _backend = NEW_NOTHROW AC_CustomControl_Empty(*this, _ahrs, _att_control, _motors, _dt);60// _backend_var_info[get_type()] = AC_CustomControl_Empty::var_info;61break;62case CustomControlType::CONT_PID:63_backend = NEW_NOTHROW AC_CustomControl_PID(*this, _ahrs, _att_control, _motors, _dt);64_backend_var_info[get_type()] = AC_CustomControl_PID::var_info;65break;66default:67return;68}6970if (_backend && _backend_var_info[get_type()]) {71AP_Param::load_object_from_eeprom(_backend, _backend_var_info[get_type()]);72}73}7475// run custom controller if it is activated by RC switch and appropriate type is selected76void AC_CustomControl::update(void)77{78if (is_safe_to_run()) {79Vector3f motor_out_rpy;8081motor_out_rpy = _backend->update();8283motor_set(motor_out_rpy);84}85}8687// choose which axis to apply custom controller output88void AC_CustomControl::motor_set(Vector3f rpy) {89if (_custom_controller_mask & (uint8_t)CustomControlOption::ROLL) {90_motors->set_roll(rpy.x);91_att_control->get_rate_roll_pid().set_integrator(0.0);92}93if (_custom_controller_mask & (uint8_t)CustomControlOption::PITCH) {94_motors->set_pitch(rpy.y);95_att_control->get_rate_pitch_pid().set_integrator(0.0);96}97if (_custom_controller_mask & (uint8_t)CustomControlOption::YAW) {98_motors->set_yaw(rpy.z);99_att_control->get_rate_yaw_pid().set_integrator(0.0);100}101}102103// move main controller's target to current states, reset filters,104// and move integrator to motor output105// to allow smooth transition to the primary controller106void AC_CustomControl::reset_main_att_controller(void)107{108// reset attitude and rate target, if feedforward is enabled109if (_att_control->get_bf_feedforward()) {110_att_control->relax_attitude_controllers();111}112113_att_control->get_rate_roll_pid().set_integrator(0.0);114_att_control->get_rate_pitch_pid().set_integrator(0.0);115_att_control->get_rate_yaw_pid().set_integrator(0.0);116}117118void AC_CustomControl::set_custom_controller(bool enabled)119{120// double logging switch makes the state change very clear in the log121log_switch();122123_custom_controller_active = false;124125// don't allow accidental main controller reset without active custom controller126if (_controller_type == CustomControlType::CONT_NONE) {127GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is not enabled");128return;129}130131// controller type is out of range132if (_controller_type > CUSTOMCONTROL_MAX_TYPES) {133GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller type is out of range");134return;135}136137// backend is not created138if (_backend == nullptr) {139GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Reboot to enable selected custom controller");140return;141}142143if (_custom_controller_mask == 0 && enabled) {144GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Axis mask is not set");145return;146}147148// reset main controller149if (!enabled) {150GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is OFF");151// don't reset if the empty backend is selected152if (_controller_type > CustomControlType::CONT_EMPTY) {153reset_main_att_controller();154}155}156157if (enabled && _controller_type > CustomControlType::CONT_NONE) {158// reset custom controller filter, integrator etc.159_backend->reset();160GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Custom controller is ON");161}162163_custom_controller_active = enabled;164165// log successful switch166log_switch();167}168169// check that RC switch is on, backend is not changed mid flight and controller type is selected170bool AC_CustomControl::is_safe_to_run(void) {171if (_custom_controller_active && (_controller_type > CustomControlType::CONT_NONE)172&& (_controller_type <= CUSTOMCONTROL_MAX_TYPES) && _backend != nullptr)173{174return true;175}176177return false;178}179180// log when the custom controller is switch into181void AC_CustomControl::log_switch(void) {182// @LoggerMessage: CC183// @Description: Custom Controller data184// @Field: TimeUS: Time since system startup185// @Field: Type: controller type186// @FieldValueEnum: Type: AC_CustomControl::CustomControlType187// @Field: Act: true if controller is active188AP::logger().Write("CC", "TimeUS,Type,Act","QBB",189AP_HAL::micros64(),190_controller_type,191_custom_controller_active);192}193194void AC_CustomControl::set_notch_sample_rate(float sample_rate)195{196#if AP_FILTER_ENABLED197if (_backend != nullptr) {198_backend->set_notch_sample_rate(sample_rate);199}200#endif201}202203#endif // AP_CUSTOMCONTROL_ENABLED204205206