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_Empty.cpp
Views: 1798
#include "AC_CustomControl_config.h"12#if AP_CUSTOMCONTROL_EMPTY_ENABLED34#include "AC_CustomControl_Empty.h"56#include <GCS_MAVLink/GCS.h>78// table of user settable parameters9const AP_Param::GroupInfo AC_CustomControl_Empty::var_info[] = {10// @Param: PARAM111// @DisplayName: Empty param112// @Description: Dummy parameter for empty custom controller backend13// @User: Advanced14AP_GROUPINFO("PARAM1", 1, AC_CustomControl_Empty, param1, 0.0f),1516// @Param: PARAM217// @DisplayName: Empty param218// @Description: Dummy parameter for empty custom controller backend19// @User: Advanced20AP_GROUPINFO("PARAM2", 2, AC_CustomControl_Empty, param2, 0.0f),2122// @Param: PARAM323// @DisplayName: Empty param324// @Description: Dummy parameter for empty custom controller backend25// @User: Advanced26AP_GROUPINFO("PARAM3", 3, AC_CustomControl_Empty, param3, 0.0f),2728AP_GROUPEND29};3031// initialize in the constructor32AC_CustomControl_Empty::AC_CustomControl_Empty(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt) :33AC_CustomControl_Backend(frontend, ahrs, att_control, motors, dt)34{35AP_Param::setup_object_defaults(this, var_info);36}3738// update controller39// return roll, pitch, yaw controller output40Vector3f AC_CustomControl_Empty::update(void)41{42// reset controller based on spool state43switch (_motors->get_spool_state()) {44case AP_Motors::SpoolState::SHUT_DOWN:45case AP_Motors::SpoolState::GROUND_IDLE:46// We are still at the ground. Reset custom controller to avoid47// build up, ex: integrator48reset();49break;5051case AP_Motors::SpoolState::THROTTLE_UNLIMITED:52case AP_Motors::SpoolState::SPOOLING_UP:53case AP_Motors::SpoolState::SPOOLING_DOWN:54// we are off the ground55break;56}5758// arducopter main attitude controller already ran59// we don't need to do anything else6061GCS_SEND_TEXT(MAV_SEVERITY_INFO, "empty custom controller working");6263// return what arducopter main controller outputted64return Vector3f(_motors->get_roll(), _motors->get_pitch(), _motors->get_yaw());65}6667// reset controller to avoid build up on the ground68// or to provide bumpless transfer from arducopter main controller69void AC_CustomControl_Empty::reset(void)70{71}7273#endif // AP_CUSTOMCONTROL_EMPTY_ENABLED747576