AC_PrecLand: remove PI controller, speed limits as they are unused

This commit is contained in:
Allan Matthew 2016-05-06 11:03:59 +09:00 committed by Randy Mackay
parent 6bcd9e6f65
commit d01db0edd6
2 changed files with 2 additions and 45 deletions

View File

@ -22,33 +22,6 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
// @User: Advanced // @User: Advanced
AP_GROUPINFO("TYPE", 1, AC_PrecLand, _type, 0), AP_GROUPINFO("TYPE", 1, AC_PrecLand, _type, 0),
// @Param: SPEED
// @DisplayName: Precision Land horizontal speed maximum in cm/s
// @Description: Precision Land horizontal speed maximum in cm/s
// @Range: 0 500
// @User: Advanced
AP_GROUPINFO("SPEED", 2, AC_PrecLand, _speed_xy, AC_PRECLAND_SPEED_XY_DEFAULT),
// @Param: VEL_P
// @DisplayName: Precision landing velocity controller P gain
// @Description: Precision landing velocity controller P gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: VEL_I
// @DisplayName: Precision landing velocity controller I gain
// @Description: Precision landing velocity controller I gain
// @Range: 0.100 5.000
// @User: Advanced
// @Param: VEL_IMAX
// @DisplayName: Precision landing velocity controller I gain maximum
// @Description: Precision landing velocity controller I gain maximum
// @Range: 0 1000
// @Units: cm/s
// @User: Standard
AP_SUBGROUPINFO(_pi_vel_xy, "VEL_", 3, AC_PrecLand, AC_PI_2D),
AP_GROUPEND AP_GROUPEND
}; };
@ -56,11 +29,9 @@ const AP_Param::GroupInfo AC_PrecLand::var_info[] = {
// Note that the Vector/Matrix constructors already implicitly zero // Note that the Vector/Matrix constructors already implicitly zero
// their values. // their values.
// //
AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav, float dt) : AC_PrecLand::AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav) :
_ahrs(ahrs), _ahrs(ahrs),
_inav(inav), _inav(inav),
_pi_vel_xy(PRECLAND_P, PRECLAND_I, PRECLAND_IMAX, PRECLAND_FILT_HZ, dt),
_dt(dt),
_have_estimate(false), _have_estimate(false),
_backend(NULL) _backend(NULL)
{ {

View File

@ -3,17 +3,8 @@
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_Math/AP_Math.h> #include <AP_Math/AP_Math.h>
#include <AC_PID/AC_PI_2D.h>
#include <AP_InertialNav/AP_InertialNav.h> #include <AP_InertialNav/AP_InertialNav.h>
// definitions
#define AC_PRECLAND_SPEED_XY_DEFAULT 100.0f // maximum horizontal speed
#define PRECLAND_P 2.0f // velocity controller P gain default
#define PRECLAND_I 1.0f // velocity controller I gain default
#define PRECLAND_IMAX 500.0f // velocity controller IMAX default
#define PRECLAND_FILT_HZ 5.0f // velocity controller filter hz
#define PRECLAND_UPDATE_TIME 0.02f // precland runs at 50hz
// declare backend classes // declare backend classes
class AC_PrecLand_Backend; class AC_PrecLand_Backend;
class AC_PrecLand_Companion; class AC_PrecLand_Companion;
@ -43,7 +34,7 @@ public:
}; };
// Constructor // Constructor
AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav, float dt); AC_PrecLand(const AP_AHRS& ahrs, const AP_InertialNav& inav);
// init - perform any required initialisation of landing controllers // init - perform any required initialisation of landing controllers
void init(); void init();
@ -83,15 +74,10 @@ private:
// references to inertial nav and ahrs libraries // references to inertial nav and ahrs libraries
const AP_AHRS& _ahrs; const AP_AHRS& _ahrs;
const AP_InertialNav& _inav; const AP_InertialNav& _inav;
AC_PI_2D _pi_vel_xy; // horizontal velocity PI controller
// parameters // parameters
AP_Int8 _enabled; // enabled/disabled and behaviour AP_Int8 _enabled; // enabled/disabled and behaviour
AP_Int8 _type; // precision landing controller type AP_Int8 _type; // precision landing controller type
AP_Float _speed_xy; // maximum horizontal speed in cm/s
// internal variables
float _dt; // time difference (in seconds) between calls from the main program
// output from sensor (stored for logging) // output from sensor (stored for logging)
Vector2f _angle_to_target; // last raw sensor angle to target Vector2f _angle_to_target; // last raw sensor angle to target