Browse Source

ArduPlane: use static method to construct AP_Arming_Plane

mission-4.1.18
Lucas De Marchi 8 years ago committed by Francisco Ferreira
parent
commit
2d2876a226
  1. 20
      ArduPlane/AP_Arming.h
  2. 2
      ArduPlane/Plane.h

20
ArduPlane/AP_Arming.h

@ -14,11 +14,16 @@ public: @@ -14,11 +14,16 @@ public:
ARMING_RUDDER_ARMDISARM = 2
};
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery) :
AP_Arming(ahrs_ref, baro, compass, battery) {
AP_Param::setup_object_defaults(this, var_info);
static AP_Arming_Plane create(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, const AP_BattMonitor &battery) {
return AP_Arming_Plane{ahrs_ref, baro, compass, battery};
}
constexpr AP_Arming_Plane(AP_Arming_Plane &&other) = default;
/* Do not allow copies */
AP_Arming_Plane(const AP_Arming_Plane &other) = delete;
AP_Arming_Plane &operator=(const AP_Baro&) = delete;
bool pre_arm_checks(bool report);
ArmingRudder rudder_arming() const { return (ArmingRudder)rudder_arming_value.get(); }
@ -27,6 +32,13 @@ public: @@ -27,6 +32,13 @@ public:
static const struct AP_Param::GroupInfo var_info[];
protected:
AP_Arming_Plane(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass,
const AP_BattMonitor &battery)
: AP_Arming(ahrs_ref, baro, compass, battery)
{
AP_Param::setup_object_defaults(this, var_info);
}
bool ins_checks(bool report);
enum HomeState home_status() const override;

2
ArduPlane/Plane.h

@ -772,7 +772,7 @@ private: @@ -772,7 +772,7 @@ private:
#endif
// Arming/Disarming mangement class
AP_Arming_Plane arming {ahrs, barometer, compass, battery};
AP_Arming_Plane arming = AP_Arming_Plane::create(ahrs, barometer, compass, battery);
AP_Param param_loader {var_info};

Loading…
Cancel
Save