diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index 993d35304f..54f3af9163 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -29,30 +29,14 @@ Copter::Copter(void) control_mode(STABILIZE), scaleLongDown(1), simple_cos_yaw(1.0f), - simple_sin_yaw(0.0f), - super_simple_last_bearing(0), super_simple_cos_yaw(1.0), - super_simple_sin_yaw(0.0f), - initial_armed_bearing(0), - climb_rate(0), - target_rangefinder_alt(0.0f), - baro_alt(0), - baro_climbrate(0.0f), land_accel_ef_filter(LAND_DETECTOR_ACCEL_LPF_CUTOFF), rc_throttle_control_in_filter(1.0f), auto_yaw_mode(AUTO_YAW_LOOK_AT_NEXT_WP), - yaw_look_at_WP_bearing(0.0f), - yaw_look_at_heading(0), - yaw_look_at_heading_slew(0), - yaw_look_ahead_bearing(0.0f), inertial_nav(ahrs), - auto_trim_counter(0), - in_mavlink_delay(false), param_loader(var_info), flightmode(&mode_stabilize) { - memset(¤t_loc, 0, sizeof(current_loc)); - // init sensor error logging flags sensor_health.baro = true; sensor_health.compass = true; diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index a8243bba82..8c02bee31f 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -269,7 +269,7 @@ private: float ekfNavVelGainScaler; // system time in milliseconds of last recorded yaw reset from ekf - uint32_t ekfYawReset_ms = 0; + uint32_t ekfYawReset_ms; int8_t ekf_primary_core; AP_SerialManager serial_manager; @@ -381,7 +381,7 @@ private: struct { uint8_t baro : 1; // true if baro is healthy uint8_t compass : 1; // true if compass is healthy - uint8_t primary_gps; // primary gps index + uint8_t primary_gps : 2; // primary gps index } sensor_health; // Motor Output