mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: use static method to construct AP_Arming_Copter
This commit is contained in:
parent
39aee74b29
commit
10529feae6
|
@ -5,16 +5,18 @@
|
|||
class AP_Arming_Copter : public AP_Arming
|
||||
{
|
||||
public:
|
||||
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav,
|
||||
const AP_InertialSensor &ins) :
|
||||
AP_Arming(ahrs_ref, baro, compass, battery),
|
||||
_inav(inav),
|
||||
_ins(ins),
|
||||
_ahrs_navekf(ahrs_ref)
|
||||
{
|
||||
static AP_Arming_Copter create(const AP_AHRS_NavEKF &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav,
|
||||
const AP_InertialSensor &ins) {
|
||||
return AP_Arming_Copter{ahrs_ref, baro, compass, battery, inav, ins};
|
||||
}
|
||||
|
||||
constexpr AP_Arming_Copter(AP_Arming_Copter &&other) = default;
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_Arming_Copter(const AP_Arming_Copter &other) = delete;
|
||||
AP_Arming_Copter &operator=(const AP_Baro&) = delete;
|
||||
|
||||
void update(void);
|
||||
bool all_checks_passing(bool arming_from_gcs);
|
||||
|
||||
|
@ -46,6 +48,15 @@ protected:
|
|||
enum HomeState home_status() const override;
|
||||
|
||||
private:
|
||||
AP_Arming_Copter(const AP_AHRS_NavEKF &ahrs_ref, const AP_Baro &baro, Compass &compass,
|
||||
const AP_BattMonitor &battery, const AP_InertialNav_NavEKF &inav,
|
||||
const AP_InertialSensor &ins)
|
||||
: AP_Arming(ahrs_ref, baro, compass, battery)
|
||||
, _inav(inav)
|
||||
, _ins(ins)
|
||||
, _ahrs_navekf(ahrs_ref)
|
||||
{
|
||||
}
|
||||
|
||||
const AP_InertialNav_NavEKF &_inav;
|
||||
const AP_InertialSensor &_ins;
|
||||
|
|
|
@ -229,7 +229,7 @@ private:
|
|||
FUNCTOR_BIND_MEMBER(&Copter::exit_mission, void));
|
||||
|
||||
// Arming/Disarming mangement class
|
||||
AP_Arming_Copter arming {ahrs, barometer, compass, battery, inertial_nav, ins};
|
||||
AP_Arming_Copter arming = AP_Arming_Copter::create(ahrs, barometer, compass, battery, inertial_nav, ins);
|
||||
|
||||
// Optical flow sensor
|
||||
#if OPTFLOW == ENABLED
|
||||
|
|
Loading…
Reference in New Issue