mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
Copter: FlightMode allow_arming format changes
non-functional change
This commit is contained in:
parent
0ac708b5a0
commit
2e71a641c3
@ -287,8 +287,6 @@ protected:
|
||||
}
|
||||
void run_autopilot() override { mission.update(); }
|
||||
|
||||
// void get_pilot_desired_angle_rates(int16_t roll_in, int16_t pitch_in, int16_t yaw_in, float &roll_out, float &pitch_out, float &yaw_out);
|
||||
|
||||
private:
|
||||
|
||||
void takeoff_run();
|
||||
@ -328,7 +326,7 @@ public:
|
||||
|
||||
bool requires_GPS() const override { return false; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return false; };
|
||||
bool allows_arming(bool from_gcs) const override { return false; }
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
void save_tuning_gains();
|
||||
@ -605,12 +603,7 @@ public:
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override {
|
||||
if (from_gcs) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
};
|
||||
bool allows_arming(bool from_gcs) const override { return from_gcs; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
void set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads);
|
||||
@ -669,12 +662,7 @@ public:
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override {
|
||||
if (from_gcs) {
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
bool allows_arming(bool from_gcs) const override { return from_gcs; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
protected:
|
||||
@ -890,9 +878,7 @@ public:
|
||||
|
||||
bool requires_GPS() const override { return true; }
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override {
|
||||
return false;
|
||||
}
|
||||
bool allows_arming(bool from_gcs) const override { return false; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
void save_position();
|
||||
|
Loading…
Reference in New Issue
Block a user