Copter: use ins singleton

This commit is contained in:
Peter Barker 2018-03-10 20:34:27 +11:00 committed by Lucas De Marchi
parent 7cc808543f
commit 2749ee9060
3 changed files with 5 additions and 8 deletions

View File

@ -8,11 +8,9 @@ public:
friend class Copter;
friend class ToyMode;
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, Compass &compass,
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav,
const AP_InertialSensor &ins)
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav)
: AP_Arming(ahrs_ref, compass, battery)
, _inav(inav)
, _ins(ins)
, _ahrs_navekf(ahrs_ref)
{
}
@ -54,7 +52,6 @@ protected:
private:
const AP_InertialNav_NavEKF &_inav;
const AP_InertialSensor &_ins;
const AP_AHRS_NavEKF &_ahrs_navekf;
void parameter_checks_pid_warning_message(bool display_failure, const char *error_msg);

View File

@ -345,7 +345,7 @@ void Copter::ten_hz_logging_loop()
pos_control->write_log();
}
if (should_log(MASK_LOG_IMU) || should_log(MASK_LOG_IMU_FAST) || should_log(MASK_LOG_IMU_RAW)) {
DataFlash.Log_Write_Vibration(ins);
DataFlash.Log_Write_Vibration();
}
if (should_log(MASK_LOG_CTUN)) {
attitude_control->control_monitor_log();
@ -378,7 +378,7 @@ void Copter::twentyfive_hz_logging()
// log IMU data if we're not already logging at the higher rate
if (should_log(MASK_LOG_IMU) && !should_log(MASK_LOG_IMU_RAW)) {
DataFlash.Log_Write_IMU(ins);
DataFlash.Log_Write_IMU();
}
#endif

View File

@ -242,7 +242,7 @@ private:
// Inertial Navigation EKF
NavEKF2 EKF2{&ahrs, rangefinder};
NavEKF3 EKF3{&ahrs, rangefinder};
AP_AHRS_NavEKF ahrs{ins, EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
AP_AHRS_NavEKF ahrs{EKF2, EKF3, AP_AHRS_NavEKF::FLAG_ALWAYS_USE_EKF};
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
SITL::SITL sitl;
@ -267,7 +267,7 @@ private:
#endif
// Arming/Disarming mangement class
AP_Arming_Copter arming{ahrs, compass, battery, inertial_nav, ins};
AP_Arming_Copter arming{ahrs, compass, battery, inertial_nav};
// Optical flow sensor
#if OPTFLOW == ENABLED