AP_AHRS: remove pointless initialisations
These are either in bss or new'd. Saves ~130 bytes
This commit is contained in:
parent
51991fdd76
commit
355752ebb8
@ -54,25 +54,10 @@ public:
|
||||
|
||||
// Constructor
|
||||
AP_AHRS() :
|
||||
roll(0.0f),
|
||||
pitch(0.0f),
|
||||
yaw(0.0f),
|
||||
roll_sensor(0),
|
||||
pitch_sensor(0),
|
||||
yaw_sensor(0),
|
||||
_vehicle_class(AHRS_VEHICLE_UNKNOWN),
|
||||
_compass(nullptr),
|
||||
_optflow(nullptr),
|
||||
_airspeed(nullptr),
|
||||
_beacon(nullptr),
|
||||
_compass_last_update(0),
|
||||
_cos_roll(1.0f),
|
||||
_cos_pitch(1.0f),
|
||||
_cos_yaw(1.0f),
|
||||
_sin_roll(0.0f),
|
||||
_sin_pitch(0.0f),
|
||||
_sin_yaw(0.0f),
|
||||
_active_accel_instance(0)
|
||||
_cos_yaw(1.0f)
|
||||
{
|
||||
_singleton = this;
|
||||
|
||||
@ -86,12 +71,6 @@ public:
|
||||
// enable centrifugal correction by default
|
||||
_flags.correct_centrifugal = true;
|
||||
|
||||
// initialise _home
|
||||
_home.options = 0;
|
||||
_home.alt = 0;
|
||||
_home.lng = 0;
|
||||
_home.lat = 0;
|
||||
|
||||
_last_trim = _trim.get();
|
||||
_rotation_autopilot_body_to_vehicle_body.from_euler(_last_trim.x, _last_trim.y, 0.0f);
|
||||
_rotation_vehicle_body_to_autopilot_body = _rotation_autopilot_body_to_vehicle_body.transposed();
|
||||
|
@ -25,28 +25,10 @@ class AP_AHRS_DCM : public AP_AHRS {
|
||||
public:
|
||||
AP_AHRS_DCM()
|
||||
: AP_AHRS()
|
||||
, _omega_I_sum_time(0.0f)
|
||||
, _renorm_val_sum(0.0f)
|
||||
, _renorm_val_count(0)
|
||||
, _error_rp(1.0f)
|
||||
, _error_yaw(1.0f)
|
||||
, _gps_last_update(0)
|
||||
, _ra_deltat(0.0f)
|
||||
, _ra_sum_start(0)
|
||||
, _last_declination(0.0f)
|
||||
, _mag_earth(1, 0)
|
||||
, _have_gps_lock(false)
|
||||
, _last_lat(0)
|
||||
, _last_lng(0)
|
||||
, _position_offset_north(0.0f)
|
||||
, _position_offset_east(0.0f)
|
||||
, _have_position(false)
|
||||
, _last_wind_time(0)
|
||||
, _last_airspeed(0.0f)
|
||||
, _last_consistent_heading(0)
|
||||
, _imu1_weight(0.5f)
|
||||
, _last_failure_ms(0)
|
||||
, _last_startup_ms(0)
|
||||
{
|
||||
_dcm_matrix.identity();
|
||||
|
||||
|
@ -36,9 +36,6 @@ AP_AHRS_NavEKF::AP_AHRS_NavEKF(NavEKF2 &_EKF2,
|
||||
AP_AHRS_DCM(),
|
||||
EKF2(_EKF2),
|
||||
EKF3(_EKF3),
|
||||
_ekf2_started(false),
|
||||
_ekf3_started(false),
|
||||
_force_ekf(false),
|
||||
_ekf_flags(flags)
|
||||
{
|
||||
_dcm_matrix.identity();
|
||||
|
Loading…
Reference in New Issue
Block a user