mirror of https://github.com/ArduPilot/ardupilot
Copter: have allows_arming take a AP_Arming::Method rather than bool from_gcs
This API predates us having the arming methods being passed around. This makes the calls look like Plane
This commit is contained in:
parent
d1fabe0c3d
commit
d387ad9921
|
@ -653,7 +653,7 @@ bool AP_Arming_Copter::arm_checks(AP_Arming::Method method)
|
|||
#endif
|
||||
|
||||
// always check if the current mode allows arming
|
||||
if (!copter.flightmode->allows_arming(method == AP_Arming::Method::MAVLINK)) {
|
||||
if (!copter.flightmode->allows_arming(method)) {
|
||||
check_failed(true, "Mode not armable");
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -118,7 +118,7 @@ void Copter::set_land_complete(bool b)
|
|||
|
||||
// trigger disarm-on-land if configured
|
||||
bool disarm_on_land_configured = (g.throttle_behavior & THR_BEHAVE_DISARM_ON_LAND_DETECT) != 0;
|
||||
const bool mode_disarms_on_land = flightmode->allows_arming(false) && !flightmode->has_manual_throttle();
|
||||
const bool mode_disarms_on_land = flightmode->allows_arming(AP_Arming::Method::LANDING) && !flightmode->has_manual_throttle();
|
||||
|
||||
if (ap.land_complete && motors->armed() && disarm_on_land_configured && mode_disarms_on_land) {
|
||||
arming.disarm(AP_Arming::Method::LANDED);
|
||||
|
|
|
@ -55,7 +55,7 @@ public:
|
|||
virtual void run() = 0;
|
||||
virtual bool requires_GPS() const = 0;
|
||||
virtual bool has_manual_throttle() const = 0;
|
||||
virtual bool allows_arming(bool from_gcs) const = 0;
|
||||
virtual bool allows_arming(AP_Arming::Method method) const = 0;
|
||||
virtual bool is_autopilot() const { return false; }
|
||||
virtual bool has_user_takeoff(bool must_navigate) const { return false; }
|
||||
virtual bool in_guided_mode() const { return false; }
|
||||
|
@ -272,7 +272,7 @@ public:
|
|||
|
||||
bool requires_GPS() const override { return false; }
|
||||
bool has_manual_throttle() const override { return true; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool init(bool ignore_checks) override;
|
||||
void exit();
|
||||
|
@ -324,7 +324,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
|
@ -354,7 +354,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;
|
||||
bool allows_arming(AP_Arming::Method method) const override;
|
||||
bool is_autopilot() const override { return true; }
|
||||
bool in_guided_mode() const override { return mode() == Auto_NavGuided; }
|
||||
|
||||
|
@ -558,7 +558,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(AP_Arming::Method method) const override { return false; }
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
void save_tuning_gains();
|
||||
|
@ -585,7 +585,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(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
void timeout_to_loiter_ms(uint32_t timeout_ms);
|
||||
|
@ -617,7 +617,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(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
@ -648,7 +648,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
protected:
|
||||
|
@ -675,7 +675,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(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
protected:
|
||||
|
@ -721,7 +721,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
|
@ -805,7 +805,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;
|
||||
bool allows_arming(AP_Arming::Method method) const override;
|
||||
bool is_autopilot() const override { return true; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool in_guided_mode() const override { return true; }
|
||||
|
@ -905,7 +905,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(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
bool is_landing() const override { return true; };
|
||||
|
@ -946,7 +946,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
@ -989,7 +989,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
@ -1074,7 +1074,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(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
bool requires_terrain_failsafe() const override { return true; }
|
||||
|
@ -1181,7 +1181,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(AP_Arming::Method method) const override { return false; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
void save_position();
|
||||
|
@ -1227,7 +1227,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
|
@ -1254,7 +1254,7 @@ public:
|
|||
|
||||
bool requires_GPS() const override { return false; }
|
||||
bool has_manual_throttle() const override { return true; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool allows_save_trim() const override { return true; }
|
||||
bool allows_autotune() const override { return true; }
|
||||
|
@ -1297,7 +1297,7 @@ public:
|
|||
|
||||
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 allows_arming(AP_Arming::Method method) const override { return false; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool logs_attitude() const override { return true; }
|
||||
|
||||
|
@ -1366,7 +1366,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 true; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
|
||||
// Throw types
|
||||
|
@ -1423,7 +1423,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(AP_Arming::Method method) const override { return false; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
bool set_velocity(const Vector3f& velocity_neu);
|
||||
|
@ -1451,7 +1451,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(AP_Arming::Method method) const override { return false; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
protected:
|
||||
|
@ -1499,7 +1499,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 true; }
|
||||
bool allows_arming(AP_Arming::Method method) const override { return true; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
|
||||
// save current position as A or B. If both A and B have been saved move to the one specified
|
||||
|
@ -1575,7 +1575,7 @@ public:
|
|||
bool is_autopilot() 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 false; };
|
||||
bool allows_arming(AP_Arming::Method method) const override { return false; };
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
|
|
|
@ -117,7 +117,7 @@ void ModeAuto::run()
|
|||
}
|
||||
}
|
||||
|
||||
bool ModeAuto::allows_arming(bool from_gcs) const
|
||||
bool ModeAuto::allows_arming(AP_Arming::Method method) const
|
||||
{
|
||||
return (copter.g2.auto_options & (uint32_t)Options::AllowArming) != 0;
|
||||
};
|
||||
|
|
|
@ -86,10 +86,10 @@ void ModeGuided::run()
|
|||
}
|
||||
}
|
||||
|
||||
bool ModeGuided::allows_arming(bool from_gcs) const
|
||||
bool ModeGuided::allows_arming(AP_Arming::Method method) const
|
||||
{
|
||||
// always allow arming from the ground station
|
||||
if (from_gcs) {
|
||||
if (method == AP_Arming::Method::MAVLINK) {
|
||||
return true;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue