#pragma once
#include "Blimp.h"
class Parameters;
class ParametersG2;
class GCS_Blimp;
class Mode
{
public:
enum class Number : uint8_t {
LAND = 0,
MANUAL = 1,
VELOCITY = 2,
LOITER = 3,
RTL = 4,
};
Mode(void);
CLASS_NO_COPY(Mode);
virtual bool init(bool ignore_checks)
{
return true;
}
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 is_autopilot() const
{
return false;
}
virtual bool has_user_takeoff(bool must_navigate) const
{
return false;
}
virtual bool in_guided_mode() const
{
return false;
}
virtual const char *name() const = 0;
virtual const char *name4() const = 0;
virtual Mode::Number number() const = 0;
virtual bool is_landing() const
{
return false;
}
virtual bool requires_terrain_failsafe() const
{
return false;
}
virtual bool get_wp(Location &loc)
{
return false;
};
virtual int32_t wp_bearing() const
{
return 0;
}
virtual float wp_distance_m() const
{
return 0.0f;
}
virtual float crosstrack_error() const
{
return 0.0f;
}
void update_navigation();
void get_pilot_input(Vector3f &pilot, float &yaw);
protected:
virtual void run_autopilot() {}
bool is_disarmed_or_landed() const;
void land_run_horizontal_control();
void land_run_vertical_control(bool pause_descent = false);
Parameters &g;
ParametersG2 &g2;
AP_InertialNav &inertial_nav;
AP_AHRS &ahrs;
Fins *&motors;
Loiter *&loiter;
RC_Channel *&channel_right;
RC_Channel *&channel_front;
RC_Channel *&channel_up;
RC_Channel *&channel_yaw;
float &G_Dt;
public:
bool set_mode(Mode::Number mode, ModeReason reason);
GCS_Blimp &gcs();
};
class ModeManual : public Mode
{
public:
using Mode::Mode;
virtual void run() override;
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 is_autopilot() const override
{
return false;
}
protected:
const char *name() const override
{
return "Manual";
}
const char *name4() const override
{
return "MANU";
}
Mode::Number number() const override { return Mode::Number::MANUAL; }
private:
};
class ModeVelocity : public Mode
{
public:
using Mode::Mode;
virtual 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 is_autopilot() const override
{
return false;
}
protected:
const char *name() const override
{
return "Velocity";
}
const char *name4() const override
{
return "VELY";
}
Mode::Number number() const override { return Mode::Number::VELOCITY; }
private:
};
class ModeLoiter : public Mode
{
public:
using Mode::Mode;
virtual bool init(bool ignore_checks) override;
virtual 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 is_autopilot() const override
{
return false;
}
protected:
const char *name() const override
{
return "Loiter";
}
const char *name4() const override
{
return "LOIT";
}
Mode::Number number() const override { return Mode::Number::LOITER; }
private:
Vector3f target_pos;
float target_yaw;
};
class ModeLand : public Mode
{
public:
using Mode::Mode;
virtual void run() override;
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;
}
protected:
const char *name() const override
{
return "Land";
}
const char *name4() const override
{
return "LAND";
}
Mode::Number number() const override { return Mode::Number::LAND; }
private:
};
class ModeRTL : public Mode
{
public:
using Mode::Mode;
virtual bool init(bool ignore_checks) override;
virtual 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 is_autopilot() const override
{
return false;
}
protected:
const char *name() const override
{
return "RTL";
}
const char *name4() const override
{
return "RTL";
}
Mode::Number number() const override { return Mode::Number::RTL; }
};