AC_PosControl: implement singleton

This commit is contained in:
Randy Mackay 2024-09-17 12:54:55 +09:00
parent 9fb8a0f1ac
commit c706d01d7f
2 changed files with 11 additions and 1 deletions

View File

@ -77,6 +77,8 @@ extern const AP_HAL::HAL& hal;
// velocity offset targets timeout if not updated within 3 seconds
#define POSCONTROL_POSVELACCEL_OFFSET_TARGET_TIMEOUT_MS 3000
AC_PosControl *AC_PosControl::_singleton;
const AP_Param::GroupInfo AC_PosControl::var_info[] = {
// 0 was used for HOVER
@ -348,6 +350,8 @@ AC_PosControl::AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav,
_jerk_max_z_cmsss(POSCONTROL_JERK_Z * 100.0)
{
AP_Param::setup_object_defaults(this, var_info);
_singleton = this;
}

View File

@ -44,7 +44,8 @@ public:
AC_PosControl(AP_AHRS_View& ahrs, const AP_InertialNav& inav,
const class AP_Motors& motors, AC_AttitudeControl& attitude_control);
// do not allow copying
CLASS_NO_COPY(AC_PosControl);
/// set_dt / get_dt - dt is the time since the last time the position controllers were updated
/// _dt should be set based on the time of the last IMU read used by these controllers
@ -451,6 +452,9 @@ public:
static void Write_PSOD(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss);
static void Write_PSOT(float pos_target_offset_cm, float pos_offset_cm, float vel_target_offset_cms, float vel_offset_cms, float accel_target_offset_cmss, float accel_offset_cmss);
// singleton
static AC_PosControl *get_singleton(void) { return _singleton; }
protected:
// get throttle using vibration-resistant calculation (uses feed forward with manually calculated gain)
@ -587,4 +591,6 @@ private:
float vel_target_offset_cms, float vel_offset_cms,
float accel_target_offset_cmss, float accel_offset_cmss);
// singleton
static AC_PosControl *_singleton;
};