@ -147,7 +147,7 @@ bool AP_Arming::is_armed()
return (Required)require.get() == Required::NO || armed;
}
uint16_t AP_Arming::get_enabled_checks()
uint32_t AP_Arming::get_enabled_checks() const
{
return checks_to_perform;
@ -84,7 +84,7 @@ public:
bool is_armed();
// get bitmask of enabled checks
uint16_t get_enabled_checks();
uint32_t get_enabled_checks() const;
// pre_arm_checks() is virtual so it can be modified in a vehicle specific subclass
virtual bool pre_arm_checks(bool report);