2022-08-04 21:26:39 -03:00
|
|
|
#pragma once
|
|
|
|
|
2024-02-14 20:40:28 -04:00
|
|
|
#include "AC_CustomControl_config.h"
|
|
|
|
|
|
|
|
#if AP_CUSTOMCONTROL_PID_ENABLED
|
|
|
|
|
2022-08-04 21:26:39 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
|
|
|
#include <AC_PID/AC_PID.h>
|
|
|
|
#include <AC_PID/AC_P.h>
|
|
|
|
|
|
|
|
#include "AC_CustomControl_Backend.h"
|
|
|
|
|
|
|
|
class AC_CustomControl_PID : public AC_CustomControl_Backend {
|
|
|
|
public:
|
2023-07-19 10:08:19 -03:00
|
|
|
AC_CustomControl_PID(AC_CustomControl& frontend, AP_AHRS_View*& ahrs, AC_AttitudeControl*& att_control, AP_MotorsMulticopter*& motors, float dt);
|
2022-08-04 21:26:39 -03:00
|
|
|
|
|
|
|
// run lowest level body-frame rate controller and send outputs to the motors
|
|
|
|
Vector3f update() override;
|
|
|
|
void reset(void) override;
|
|
|
|
|
2023-08-10 08:09:49 -03:00
|
|
|
// set the PID notch sample rates
|
|
|
|
void set_notch_sample_rate(float sample_rate) override;
|
|
|
|
|
2022-08-04 21:26:39 -03:00
|
|
|
// user settable parameters
|
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
|
|
|
|
|
|
|
protected:
|
|
|
|
// put controller related variable here
|
2023-06-13 02:23:05 -03:00
|
|
|
float _dt;
|
2022-08-04 21:26:39 -03:00
|
|
|
|
|
|
|
// angle P controller objects
|
|
|
|
AC_P _p_angle_roll2;
|
|
|
|
AC_P _p_angle_pitch2;
|
|
|
|
AC_P _p_angle_yaw2;
|
|
|
|
|
|
|
|
// rate PID controller objects
|
|
|
|
AC_PID _pid_atti_rate_roll;
|
|
|
|
AC_PID _pid_atti_rate_pitch;
|
|
|
|
AC_PID _pid_atti_rate_yaw;
|
|
|
|
};
|
|
|
|
|
2024-02-14 20:40:28 -04:00
|
|
|
#endif // AP_CUSTOMCONTROL_PID_ENABLED
|