Copter: FlightMode - convert DRIFT flight mode

This commit is contained in:
Peter Barker 2016-03-22 17:56:08 +11:00 committed by Randy Mackay
parent 682f3c0e7e
commit 6a38664ff4
4 changed files with 40 additions and 17 deletions

View File

@ -817,9 +817,6 @@ private:
bool brake_init(bool ignore_checks);
void brake_run();
void brake_timeout_to_loiter_ms(uint32_t timeout_ms);
bool drift_init(bool ignore_checks);
void drift_run();
float get_throttle_assist(float velz, float pilot_throttle_scaled);
bool flip_init(bool ignore_checks);
void flip_run();
bool guided_nogps_init(bool ignore_checks);
@ -1067,6 +1064,8 @@ private:
Copter::FlightMode_CIRCLE flightmode_circle{*this, circle_nav};
Copter::FlightMode_DRIFT flightmode_drift{*this};
Copter::FlightMode_GUIDED flightmode_guided{*this};
Copter::FlightMode_LAND flightmode_land{*this};

View File

@ -577,3 +577,32 @@ private:
// Loiter timer - Records how long we have been in loiter
uint32_t _loiter_start_time = 0;
};
class FlightMode_DRIFT : public FlightMode {
public:
FlightMode_DRIFT(Copter &copter) :
Copter::FlightMode(copter)
{ }
virtual bool init(bool ignore_checks) override;
virtual void run() override; // should be called at 100hz or more
virtual bool requires_GPS() const override { return true; }
virtual bool has_manual_throttle() const override { return false; }
virtual bool allows_arming(bool from_gcs) const override { return true; };
virtual bool is_autopilot() const override { return false; }
protected:
const char *name() const override { return "DRIFT"; }
const char *name4() const override { return "DRIF"; }
private:
float get_throttle_assist(float velz, float pilot_throttle_scaled);
};

View File

@ -27,9 +27,9 @@
#endif
// drift_init - initialise drift controller
bool Copter::drift_init(bool ignore_checks)
bool Copter::FlightMode_DRIFT::init(bool ignore_checks)
{
if (position_ok() || ignore_checks) {
if (_copter.position_ok() || ignore_checks) {
return true;
}else{
return false;
@ -38,7 +38,7 @@ bool Copter::drift_init(bool ignore_checks)
// drift_run - runs the drift controller
// should be called at 100hz or more
void Copter::drift_run()
void Copter::FlightMode_DRIFT::run()
{
static float breaker = 0.0f;
static float roll_input = 0.0f;
@ -59,7 +59,7 @@ void Copter::drift_run()
}
// convert pilot input to lean angles
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, aparm.angle_max);
get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, _copter.aparm.angle_max);
// get pilot's desired throttle
pilot_throttle_scaled = get_pilot_desired_throttle(channel_throttle->get_control_in());
@ -108,7 +108,7 @@ void Copter::drift_run()
}
// get_throttle_assist - return throttle output (range 0 ~ 1) based on pilot input and z-axis velocity
float Copter::get_throttle_assist(float velz, float pilot_throttle_scaled)
float Copter::FlightMode_DRIFT::get_throttle_assist(float velz, float pilot_throttle_scaled)
{
// throttle assist - adjusts throttle to slow the vehicle's vertical velocity
// Only active when pilot's throttle is between 213 ~ 787

View File

@ -103,7 +103,10 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
break;
case DRIFT:
success = drift_init(ignore_checks);
success = flightmode_drift.init(ignore_checks);
if (success) {
flightmode = &flightmode_drift;
}
break;
case SPORT:
@ -212,10 +215,6 @@ void Copter::update_flight_mode()
switch (control_mode) {
case DRIFT:
drift_run();
break;
case SPORT:
sport_run();
break;
@ -323,7 +322,6 @@ bool Copter::mode_requires_GPS()
}
switch (control_mode) {
case SMART_RTL:
case DRIFT:
case POSHOLD:
case BRAKE:
case AVOID_ADSB:
@ -385,9 +383,6 @@ void Copter::notify_flight_mode()
// set flight mode string
switch (control_mode) {
case DRIFT:
notify.set_flight_mode_str("DRIF");
break;
case SPORT:
notify.set_flight_mode_str("SPRT");
break;