Browse Source

Rover: use singletons in AP_Arming

mission-4.1.18
Peter Barker 7 years ago committed by Peter Barker
parent
commit
ea12f6caec
  1. 2
      APMrover2/AP_Arming.cpp
  2. 10
      APMrover2/AP_Arming.h
  3. 2
      APMrover2/Rover.h

2
APMrover2/AP_Arming.cpp

@ -67,7 +67,7 @@ bool AP_Arming_Rover::fence_checks(bool report)
{ {
// check fence is initialised // check fence is initialised
const char *fail_msg = nullptr; 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) { if (report && fail_msg != nullptr) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Fence : %s", fail_msg); gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Fence : %s", fail_msg);
} }

10
APMrover2/AP_Arming.h

@ -9,12 +9,8 @@
class AP_Arming_Rover : public AP_Arming class AP_Arming_Rover : public AP_Arming
{ {
public: public:
AP_Arming_Rover(const AP_AHRS &ahrs_ref, Compass &compass,
const AP_BattMonitor &battery, const AC_Fence &fence) AP_Arming_Rover() : AP_Arming() { }
: AP_Arming(ahrs_ref, compass, battery),
_fence(fence)
{
}
/* Do not allow copies */ /* Do not allow copies */
AP_Arming_Rover(const AP_Arming_Rover &other) = delete; AP_Arming_Rover(const AP_Arming_Rover &other) = delete;
@ -29,5 +25,5 @@ protected:
bool proximity_check(bool report); bool proximity_check(bool report);
private: private:
const AC_Fence& _fence;
}; };

2
APMrover2/Rover.h

@ -179,7 +179,7 @@ private:
#endif #endif
// Arming/Disarming management class // Arming/Disarming management class
AP_Arming_Rover arming{ahrs, compass, battery, g2.fence}; AP_Arming_Rover arming;
AP_L1_Control L1_controller{ahrs, nullptr}; AP_L1_Control L1_controller{ahrs, nullptr};

Loading…
Cancel
Save