CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AC_CustomControl/AC_CustomControl_PID.h
Views: 1798
1
#pragma once
2
3
#include "AC_CustomControl_config.h"
4
5
#if AP_CUSTOMCONTROL_PID_ENABLED
6
7
#include <AP_Common/AP_Common.h>
8
#include <AP_Param/AP_Param.h>
9
#include <AC_PID/AC_PID.h>
10
#include <AC_PID/AC_P.h>
11
12
#include "AC_CustomControl_Backend.h"
13
14
class AC_CustomControl_PID : public AC_CustomControl_Backend {
15
public:
16
AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
17
18
// run lowest level body-frame rate controller and send outputs to the motors
19
Vector3f update() override;
20
void reset(void) override;
21
22
// set the PID notch sample rates
23
void set_notch_sample_rate(float sample_rate) override;
24
25
// user settable parameters
26
static const struct AP_Param::GroupInfo var_info[];
27
28
protected:
29
// put controller related variable here
30
float _dt;
31
32
// angle P controller objects
33
AC_P _p_angle_roll2;
34
AC_P _p_angle_pitch2;
35
AC_P _p_angle_yaw2;
36
37
// rate PID controller objects
38
AC_PID _pid_atti_rate_roll;
39
AC_PID _pid_atti_rate_pitch;
40
AC_PID _pid_atti_rate_yaw;
41
};
42
43
#endif // AP_CUSTOMCONTROL_PID_ENABLED
44
45