mirror of https://github.com/ArduPilot/ardupilot
AC_Autorotation: remove unused variables
This commit is contained in:
parent
57373180d1
commit
12af51e356
|
@ -119,8 +119,7 @@ const AP_Param::GroupInfo AC_Autorotation::var_info[] = {
|
|||
};
|
||||
|
||||
// Constructor
|
||||
AC_Autorotation::AC_Autorotation(AP_InertialNav& inav) :
|
||||
_inav(inav),
|
||||
AC_Autorotation::AC_Autorotation() :
|
||||
_p_hs(HS_CONTROLLER_HEADSPEED_P),
|
||||
_p_fw_vel(AP_FW_VEL_P)
|
||||
{
|
||||
|
|
|
@ -18,7 +18,7 @@ class AC_Autorotation
|
|||
public:
|
||||
|
||||
//Constructor
|
||||
AC_Autorotation(AP_InertialNav& inav);
|
||||
AC_Autorotation();
|
||||
|
||||
//--------Functions--------
|
||||
void init_hs_controller(void); // Initialise head speed controller
|
||||
|
@ -51,7 +51,6 @@ private:
|
|||
float _current_rpm;
|
||||
float _collective_out;
|
||||
float _head_speed_error; // Error between target head speed and current head speed. Normalised by head speed set point RPM.
|
||||
uint16_t _log_counter;
|
||||
float _col_cutoff_freq; // Lowpass filter cutoff frequency (Hz) for collective.
|
||||
uint8_t _unhealthy_rpm_counter; // Counter used to track RPM sensor unhealthy signal.
|
||||
uint8_t _healthy_rpm_counter; // Counter used to track RPM sensor healthy signal.
|
||||
|
@ -61,7 +60,6 @@ private:
|
|||
|
||||
float _vel_target; // Forward velocity target.
|
||||
float _pitch_target; // Pitch angle target.
|
||||
float _vel_error; // Velocity error.
|
||||
float _accel_max; // Maximum acceleration limit.
|
||||
int16_t _speed_forward_last; // The forward speed calculated in the previous cycle.
|
||||
bool _flag_limit_accel; // Maximum acceleration limit reached flag.
|
||||
|
@ -101,8 +99,4 @@ private:
|
|||
|
||||
// low pass filter for collective trim
|
||||
LowPassFilterFloat col_trim_lpf;
|
||||
|
||||
//--------References to Other Libraries--------
|
||||
AP_InertialNav& _inav;
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue