Path: blob/master/libraries/AC_CustomControl/AC_CustomControl_PID.h
9445 views
#pragma once12#include "AC_CustomControl_config.h"34#if AP_CUSTOMCONTROL_PID_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_Param/AP_Param.h>8#include <AC_PID/AC_PID.h>9#include <AC_PID/AC_P.h>1011#include "AC_CustomControl_Backend.h"1213class AC_CustomControl_PID : public AC_CustomControl_Backend {14public:15AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);1617// run lowest level body-frame rate controller and send outputs to the motors18Vector3f update() override;19void reset(void) override;2021// set the PID notch sample rates22void set_notch_sample_rate(float sample_rate) override;2324// user settable parameters25static const struct AP_Param::GroupInfo var_info[];2627protected:28// put controller related variable here29float _dt;3031// angle P controller objects32AC_P _p_angle_roll2;33AC_P _p_angle_pitch2;34AC_P _p_angle_yaw2;3536// rate PID controller objects37AC_PID _pid_atti_rate_roll;38AC_PID _pid_atti_rate_pitch;39AC_PID _pid_atti_rate_yaw;40};4142#endif // AP_CUSTOMCONTROL_PID_ENABLED434445