mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
4c9f48244e
See discussion here: https://github.com/ArduPilot/ardupilot/issues/7331 we were getting some uninitialised variables. While it only showed up in AP_SbusOut, it means we can't be sure it won't happen on other objects, so safest to remove the approach Thanks to assistance from Lucas, Peter and Francisco
24 lines
645 B
C++
24 lines
645 B
C++
#pragma once
|
|
|
|
#include <AP_Arming/AP_Arming.h>
|
|
|
|
class AP_Arming_Sub : public AP_Arming {
|
|
public:
|
|
AP_Arming_Sub(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
|
const AP_BattMonitor &battery)
|
|
: AP_Arming(ahrs_ref, baro, compass, battery)
|
|
{
|
|
}
|
|
|
|
/* Do not allow copies */
|
|
AP_Arming_Sub(const AP_Arming_Sub &other) = delete;
|
|
AP_Arming_Sub &operator=(const AP_Baro&) = delete;
|
|
|
|
bool rc_calibration_checks(bool report) override;
|
|
bool pre_arm_checks(bool report) override;
|
|
|
|
protected:
|
|
bool ins_checks(bool report) override;
|
|
enum HomeState home_status() const override;
|
|
};
|