mirror of https://github.com/ArduPilot/ardupilot
Rover: use singletons in AP_Arming
This commit is contained in:
parent
a1f29e92d1
commit
ea12f6caec
|
@ -67,7 +67,7 @@ bool AP_Arming_Rover::fence_checks(bool report)
|
|||
{
|
||||
// check fence is initialised
|
||||
const char *fail_msg = nullptr;
|
||||
if (!_fence.pre_arm_check(fail_msg)) {
|
||||
if (!rover.g2.fence.pre_arm_check(fail_msg)) {
|
||||
if (report && fail_msg != nullptr) {
|
||||
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Fence : %s", fail_msg);
|
||||
}
|
||||
|
|
|
@ -9,12 +9,8 @@
|
|||
class AP_Arming_Rover : public AP_Arming
|
||||
{
|
||||
public:
|
||||
AP_Arming_Rover(const AP_AHRS &ahrs_ref, Compass &compass,
|
||||
const AP_BattMonitor &battery, const AC_Fence &fence)
|
||||
: AP_Arming(ahrs_ref, compass, battery),
|
||||
_fence(fence)
|
||||
{
|
||||
}
|
||||
|
||||
AP_Arming_Rover() : AP_Arming() { }
|
||||
|
||||
/* Do not allow copies */
|
||||
AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
|
||||
|
@ -29,5 +25,5 @@ protected:
|
|||
bool proximity_check(bool report);
|
||||
|
||||
private:
|
||||
const AC_Fence& _fence;
|
||||
|
||||
};
|
||||
|
|
|
@ -179,7 +179,7 @@ private:
|
|||
#endif
|
||||
|
||||
// Arming/Disarming management class
|
||||
AP_Arming_Rover arming{ahrs, compass, battery, g2.fence};
|
||||
AP_Arming_Rover arming;
|
||||
|
||||
AP_L1_Control L1_controller{ahrs, nullptr};
|
||||
|
||||
|
|
Loading…
Reference in New Issue