AC_AttControl: remove deprecated trigger_xy method

This commit is contained in:
Randy Mackay 2015-01-07 12:34:33 +09:00
parent be5bf91e92
commit 2a5a133bbf
2 changed files with 0 additions and 5 deletions

View File

@ -54,7 +54,6 @@ AC_PosControl::AC_PosControl(const AP_AHRS& ahrs, const AP_InertialNav& inav,
AP_Param::setup_object_defaults(this, var_info);
// initialise flags
_flags.force_recalc_xy = false;
#if HAL_CPU_CLASS >= HAL_CPU_CLASS_150
_flags.slow_cpu = false;
#else

View File

@ -192,9 +192,6 @@ public:
/// when update_vel_controller_xyz is next called the position target is moved based on the desired velocity
void set_desired_velocity(const Vector3f &des_vel) { _vel_desired = des_vel; freeze_ff_xy(); }
/// trigger_xy - used to notify the position controller than an update has been made to the position or desired velocity so that the position controller will run as soon as possible after the update
void trigger_xy() { _flags.force_recalc_xy = true; }
/// freeze_ff_z - used to stop the feed forward being calculated during a known discontinuity
void freeze_ff_z() { _flags.freeze_ff_z = true; }
@ -263,7 +260,6 @@ private:
struct poscontrol_flags {
uint8_t recalc_leash_z : 1; // 1 if we should recalculate the z axis leash length
uint8_t recalc_leash_xy : 1; // 1 if we should recalculate the xy axis leash length
uint8_t force_recalc_xy : 1; // 1 if we want the xy position controller to run at it's next possible time. set by loiter and wp controllers after they have updated the target position.
uint8_t slow_cpu : 1; // 1 if we are running on a slow_cpu machine. xy position control is broken up into multiple steps
uint8_t reset_desired_vel_to_pos: 1; // 1 if we should reset the rate_to_accel_xy step
uint8_t reset_rate_to_accel_xy : 1; // 1 if we should reset the rate_to_accel_xy step