From 56c6233be9f754668fa4c99503d2c7ad83bcaebe Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 3 Jul 2022 19:57:49 +0100 Subject: [PATCH] AC_AttitudeControl: remove PosControl_Sub --- .../AC_AttitudeControl/AC_PosControl_Sub.cpp | 2 -- .../AC_AttitudeControl/AC_PosControl_Sub.h | 24 ------------------- 2 files changed, 26 deletions(-) delete mode 100644 libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp delete mode 100644 libraries/AC_AttitudeControl/AC_PosControl_Sub.h diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp b/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp deleted file mode 100644 index d309c137fb..0000000000 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.cpp +++ /dev/null @@ -1,2 +0,0 @@ -#include "AC_PosControl_Sub.h" - diff --git a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h b/libraries/AC_AttitudeControl/AC_PosControl_Sub.h deleted file mode 100644 index 03c73aded4..0000000000 --- a/libraries/AC_AttitudeControl/AC_PosControl_Sub.h +++ /dev/null @@ -1,24 +0,0 @@ -#pragma once - -#include "AC_PosControl.h" - -#define POSCONTROL_JERK_RATIO 1.0f // Defines the time it takes to reach the requested acceleration - -class AC_PosControl_Sub : public AC_PosControl { -public: - using AC_PosControl::AC_PosControl; - - /// set_alt_max - sets maximum altitude above the ekf origin in cm - /// only enforced when set_pos_target_z_from_climb_rate_cm is used - /// set to zero to disable limit - void set_alt_max(float alt) { _alt_max = alt; } - - /// set_alt_min - sets the minimum altitude (maximum depth) in cm - /// only enforced when set_pos_target_z_from_climb_rate_cm is used - /// set to zero to disable limit - void set_alt_min(float alt) { _alt_min = alt; } - -private: - float _alt_max; // max altitude - should be updated from the main code with altitude limit from fence - float _alt_min; // min altitude - should be updated from the main code with altitude limit from fence -};