mirror of https://github.com/ArduPilot/ardupilot
Sub: motor detection mode does not require valid position
This commit is contained in:
parent
96682b1b1b
commit
9fdf52c59c
|
@ -472,7 +472,7 @@ public:
|
|||
virtual void run() override;
|
||||
|
||||
bool init(bool ignore_checks) override;
|
||||
bool requires_GPS() const override { return true; }
|
||||
bool requires_GPS() const override { return false; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
|
Loading…
Reference in New Issue