mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
Copter: remove unused scaleLongDown member
This commit is contained in:
parent
c9c802f617
commit
31f796f0c5
@ -27,7 +27,6 @@ Copter::Copter(void)
|
|||||||
: logger(g.log_bitmask),
|
: logger(g.log_bitmask),
|
||||||
flight_modes(&g.flight_mode1),
|
flight_modes(&g.flight_mode1),
|
||||||
control_mode(STABILIZE),
|
control_mode(STABILIZE),
|
||||||
scaleLongDown(1),
|
|
||||||
simple_cos_yaw(1.0f),
|
simple_cos_yaw(1.0f),
|
||||||
super_simple_cos_yaw(1.0),
|
super_simple_cos_yaw(1.0),
|
||||||
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
|
land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF),
|
||||||
|
@ -386,10 +386,6 @@ private:
|
|||||||
MOTOR_CLASS *motors;
|
MOTOR_CLASS *motors;
|
||||||
const struct AP_Param::GroupInfo *motors_var_info;
|
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;
|
int32_t _home_bearing;
|
||||||
uint32_t _home_distance;
|
uint32_t _home_distance;
|
||||||
|
|
||||||
|
@ -78,8 +78,6 @@ bool Copter::set_home(const Location& loc, bool lock)
|
|||||||
|
|
||||||
// init inav and compass declination
|
// init inav and compass declination
|
||||||
if (!home_was_set) {
|
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
|
// record home is set
|
||||||
Log_Write_Event(DATA_SET_HOME);
|
Log_Write_Event(DATA_SET_HOME);
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user