Copter: current_mode_has_user_takeoff -> Mode::has_user_takeoff
This commit is contained in:
parent
70d159cb38
commit
cb26ff64b3
@ -923,8 +923,6 @@ private:
|
||||
const char* get_frame_string();
|
||||
void allocate_motors(void);
|
||||
|
||||
// takeoff.cpp
|
||||
bool current_mode_has_user_takeoff(bool must_navigate);
|
||||
bool do_user_takeoff(float takeoff_alt_cm, bool must_navigate);
|
||||
void takeoff_timer_start(float alt_cm);
|
||||
void takeoff_stop();
|
||||
|
@ -85,6 +85,8 @@ protected:
|
||||
|
||||
virtual const char *name() const = 0;
|
||||
|
||||
virtual bool has_user_takeoff(bool must_navigate) const { return false; }
|
||||
|
||||
// returns a string for this flightmode, exactly 4 bytes
|
||||
virtual const char *name4() const = 0;
|
||||
|
||||
@ -220,6 +222,9 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
@ -264,6 +269,10 @@ public:
|
||||
|
||||
bool landing_gear_should_be_deployed() const override;
|
||||
|
||||
// return true if this flight mode supports user takeoff
|
||||
// must_nagivate is true if mode must also control horizontal position
|
||||
virtual bool has_user_takeoff(bool must_navigate) const { return false; }
|
||||
|
||||
void payload_place_start();
|
||||
|
||||
// only out here temporarily
|
||||
@ -675,6 +684,9 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
}
|
||||
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -755,6 +767,7 @@ public:
|
||||
bool allows_arming(bool from_gcs) const override { return from_gcs; }
|
||||
bool is_autopilot() const override { return true; }
|
||||
bool in_guided_mode() const { return true; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
|
||||
void set_angle(const Quaternion &q, float climb_rate_cms, bool use_yaw_rate, float yaw_rate_rads);
|
||||
bool set_destination(const Vector3f& destination, bool use_yaw = false, float yaw_cd = 0.0, bool use_yaw_rate = false, float yaw_rate_cds = 0.0, bool yaw_relative = false);
|
||||
@ -868,6 +881,7 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
void set_precision_loiter_enabled(bool value) { _precision_loiter_enabled = value; }
|
||||
@ -908,6 +922,7 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override { return true; }
|
||||
|
||||
protected:
|
||||
|
||||
@ -1048,6 +1063,9 @@ public:
|
||||
bool has_manual_throttle() const override { return false; }
|
||||
bool allows_arming(bool from_gcs) const override { return true; };
|
||||
bool is_autopilot() const override { return false; }
|
||||
bool has_user_takeoff(bool must_navigate) const override {
|
||||
return !must_navigate;
|
||||
}
|
||||
|
||||
protected:
|
||||
|
||||
|
@ -5,28 +5,10 @@
|
||||
// A safe takeoff speed is calculated and used to calculate a time_ms
|
||||
// the pos_control target is then slowly increased until time_ms expires
|
||||
|
||||
// return true if this flight mode supports user takeoff
|
||||
// must_nagivate is true if mode must also control horizontal position
|
||||
bool Copter::current_mode_has_user_takeoff(bool must_navigate)
|
||||
{
|
||||
switch (control_mode) {
|
||||
case GUIDED:
|
||||
case LOITER:
|
||||
case POSHOLD:
|
||||
return true;
|
||||
case ALT_HOLD:
|
||||
case SPORT:
|
||||
case FLOWHOLD:
|
||||
return !must_navigate;
|
||||
default:
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
// initiate user takeoff - called when MAVLink TAKEOFF command is received
|
||||
bool Copter::do_user_takeoff(float takeoff_alt_cm, bool must_navigate)
|
||||
{
|
||||
if (motors->armed() && ap.land_complete && current_mode_has_user_takeoff(must_navigate) && takeoff_alt_cm > current_loc.alt) {
|
||||
if (motors->armed() && ap.land_complete && flightmode->has_user_takeoff(must_navigate) && takeoff_alt_cm > current_loc.alt) {
|
||||
|
||||
#if FRAME_CONFIG == HELI_FRAME
|
||||
// Helicopters should return false if MAVlink takeoff command is received while the rotor is not spinning
|
||||
|
Loading…
Reference in New Issue
Block a user