ArduSub: use static method to construct AP_Arming_Sub

This also fix a bug of calling AP_Param::setup_object_defaults() on the
parent.
This commit is contained in:
Lucas De Marchi 2017-08-30 13:25:42 -07:00 committed by Francisco Ferreira
parent 2d2876a226
commit eed3c83079
2 changed files with 15 additions and 5 deletions

View File

@ -4,16 +4,26 @@
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) {
AP_Param::setup_object_defaults(this, var_info);
static AP_Arming_Sub create(const AP_AHRS &ahrs_ref, const AP_Baro &baro, Compass &compass, const AP_BattMonitor &battery) {
return AP_Arming_Sub{ahrs_ref, baro, compass, battery};
}
constexpr AP_Arming_Sub(AP_Arming_Sub &&other) = default;
/* Do not allow copies */
AP_Arming_Sub(const AP_Arming_Sub &other) = delete;
AP_Arming_Sub &operator=(const AP_Baro&) = delete;
bool rc_check(bool report=true);
bool pre_arm_checks(bool report) override;
protected:
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)
{
}
bool ins_checks(bool report) override;
enum HomeState home_status() const override;
};

View File

@ -328,7 +328,7 @@ private:
// Battery Sensors
AP_BattMonitor battery;
AP_Arming_Sub arming {ahrs, barometer, compass, battery};
AP_Arming_Sub arming = AP_Arming_Sub::create(ahrs, barometer, compass, battery);
// Altitude
// The cm/s we are moving up or down based on filtered data - Positive = UP