Copter: FlightMode - convert SPORT flight mode

This commit is contained in:
Peter Barker 2016-03-22 19:07:23 +11:00 committed by Randy Mackay
parent 6a38664ff4
commit 5e3e831152
4 changed files with 36 additions and 13 deletions

View File

@ -852,8 +852,6 @@ private:
void smart_rtl_land(); void smart_rtl_land();
void smart_rtl_save_position(); void smart_rtl_save_position();
bool sport_init(bool ignore_checks);
void sport_run();
void crash_check(); void crash_check();
void parachute_check(); void parachute_check();
void parachute_release(); void parachute_release();
@ -1080,6 +1078,7 @@ private:
Copter::FlightMode_STABILIZE flightmode_stabilize{*this}; Copter::FlightMode_STABILIZE flightmode_stabilize{*this};
#endif #endif
Copter::FlightMode_SPORT flightmode_sport{*this};
public: public:
void mavlink_delay_cb(); void mavlink_delay_cb();

View File

@ -606,3 +606,30 @@ private:
float get_throttle_assist(float velz, float pilot_throttle_scaled); float get_throttle_assist(float velz, float pilot_throttle_scaled);
}; };
class FlightMode_SPORT : public FlightMode {
public:
FlightMode_SPORT(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 false; }
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 "SPORT"; }
const char *name4() const override { return "SPRT"; }
private:
};

View File

@ -5,7 +5,7 @@
*/ */
// sport_init - initialise sport controller // sport_init - initialise sport controller
bool Copter::sport_init(bool ignore_checks) bool Copter::FlightMode_SPORT::init(bool ignore_checks)
{ {
// initialize vertical speed and acceleration // initialize vertical speed and acceleration
pos_control->set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up); pos_control->set_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
@ -22,7 +22,7 @@ bool Copter::sport_init(bool ignore_checks)
// sport_run - runs the sport controller // sport_run - runs the sport controller
// should be called at 100hz or more // should be called at 100hz or more
void Copter::sport_run() void Copter::FlightMode_SPORT::run()
{ {
SportModeState sport_state; SportModeState sport_state;
float takeoff_climb_rate = 0.0f; float takeoff_climb_rate = 0.0f;
@ -51,6 +51,7 @@ void Copter::sport_run()
int32_t pitch_angle = wrap_180_cd(att_target.y); int32_t pitch_angle = wrap_180_cd(att_target.y);
target_pitch_rate -= constrain_int32(pitch_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_pitch; target_pitch_rate -= constrain_int32(pitch_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_pitch;
AP_Vehicle::MultiCopter &aparm = _copter.aparm;
if (roll_angle > aparm.angle_max){ if (roll_angle > aparm.angle_max){
target_roll_rate -= g.acro_rp_p*(roll_angle-aparm.angle_max); target_roll_rate -= g.acro_rp_p*(roll_angle-aparm.angle_max);
}else if (roll_angle < -aparm.angle_max) { }else if (roll_angle < -aparm.angle_max) {
@ -156,7 +157,7 @@ void Copter::sport_run()
attitude_control->input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate); attitude_control->input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate);
// adjust climb rate using rangefinder // adjust climb rate using rangefinder
if (rangefinder_alt_ok()) { if (_copter.rangefinder_alt_ok()) {
// if rangefinder is ok, use surface tracking // if rangefinder is ok, use surface tracking
target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt); target_climb_rate = get_surface_tracking_climb_rate(target_climb_rate, pos_control->get_alt_target(), G_Dt);
} }

View File

@ -110,7 +110,10 @@ bool Copter::set_mode(control_mode_t mode, mode_reason_t reason)
break; break;
case SPORT: case SPORT:
success = sport_init(ignore_checks); success = flightmode_sport.init(ignore_checks);
if (success) {
flightmode = &flightmode_sport;
}
break; break;
case FLIP: case FLIP:
@ -215,10 +218,6 @@ void Copter::update_flight_mode()
switch (control_mode) { switch (control_mode) {
case SPORT:
sport_run();
break;
case FLIP: case FLIP:
flip_run(); flip_run();
break; break;
@ -383,9 +382,6 @@ void Copter::notify_flight_mode()
// set flight mode string // set flight mode string
switch (control_mode) { switch (control_mode) {
case SPORT:
notify.set_flight_mode_str("SPRT");
break;
case FLIP: case FLIP:
notify.set_flight_mode_str("FLIP"); notify.set_flight_mode_str("FLIP");
break; break;