mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Copter: mark ModeSystemID as has_manual_throttle, no-arm and no-gps
This has implications for many things, like smoothing transition to auto modes, and for arming
This commit is contained in:
parent
9e97c2e095
commit
3af006019b
@ -1295,11 +1295,12 @@ public:
|
||||
bool init(bool ignore_checks) override;
|
||||
void run() override;
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool requires_GPS() const override { return false; }
|
||||
bool has_manual_throttle() const override { return true; }
|
||||
bool allows_arming(bool from_gcs) const override { return false; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool logs_attitude() const override { return true; }
|
||||
|
||||
void set_magnitude(float input) { waveform_magnitude = input; }
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
Loading…
Reference in New Issue
Block a user