Copter: remove unused scaleLongDown member

This commit is contained in:
Peter Barker 2019-02-15 12:30:56 +11:00 committed by Randy Mackay
parent c9c802f617
commit 31f796f0c5
3 changed files with 0 additions and 7 deletions

View File

@ -27,7 +27,6 @@ Copter::Copter(void)
: logger(g.log_bitmask),
flight_modes(&g.flight_mode1),
control_mode(STABILIZE),
scaleLongDown(1),
simple_cos_yaw(1.0f),
super_simple_cos_yaw(1.0),
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),

View File

@ -386,10 +386,6 @@ private:
MOTOR_CLASS *motors;
const struct AP_Param::GroupInfo *motors_var_info;
// GPS variables
// Sometimes we need to remove the scaling for distance calcs
float scaleLongDown;
int32_t _home_bearing;
uint32_t _home_distance;

View File

@ -78,8 +78,6 @@ bool Copter::set_home(const Location& loc, bool lock)
// init inav and compass declination
if (!home_was_set) {
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
scaleLongDown = longitude_scale(loc);
// record home is set
Log_Write_Event(DATA_SET_HOME);