#include "Copter.h" #if MODE_SPORT_ENABLED /* * Init and run calls for sport flight mode */ // sport_init - initialise sport controller bool ModeSport::init(bool ignore_checks) { // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); pos_control->set_correction_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); // initialise the vertical position controller if (!pos_control->is_active_z()) { pos_control->init_z_controller(); } return true; } // sport_run - runs the sport controller // should be called at 100hz or more void ModeSport::run() { // set vertical speed and acceleration limits pos_control->set_max_speed_accel_z(-get_pilot_speed_dn(), g.pilot_speed_up, g.pilot_accel_z); // apply SIMPLE mode transform update_simple_mode(); // get pilot's desired roll and pitch rates // calculate rate requests float target_roll_rate = channel_roll->get_control_in() * g2.command_model_acro_rp.get_rate() * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; float target_pitch_rate = channel_pitch->get_control_in() * g2.command_model_acro_rp.get_rate() * 100.0 / ROLL_PITCH_YAW_INPUT_MAX; // get attitude targets const Vector3f att_target = attitude_control->get_att_target_euler_cd(); // Calculate trainer mode earth frame rate command for roll int32_t roll_angle = wrap_180_cd(att_target.x); target_roll_rate -= constrain_int32(roll_angle, -ACRO_LEVEL_MAX_ANGLE, ACRO_LEVEL_MAX_ANGLE) * g.acro_balance_roll; // Calculate trainer mode earth frame rate command for pitch 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; const float angle_max = copter.aparm.angle_max; if (roll_angle > angle_max){ target_roll_rate += sqrt_controller(angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); }else if (roll_angle < -angle_max) { target_roll_rate += sqrt_controller(-angle_max - roll_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_roll_max_cdss(), G_Dt); } if (pitch_angle > angle_max){ target_pitch_rate += sqrt_controller(angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); }else if (pitch_angle < -angle_max) { target_pitch_rate += sqrt_controller(-angle_max - pitch_angle, g2.command_model_acro_rp.get_rate() * 100.0 / ACRO_LEVEL_MAX_OVERSHOOT, attitude_control->get_accel_pitch_max_cdss(), G_Dt); } // get pilot's desired yaw rate float target_yaw_rate = get_pilot_desired_yaw_rate(); // get pilot desired climb rate float target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); target_climb_rate = constrain_float(target_climb_rate, -get_pilot_speed_dn(), g.pilot_speed_up); // Sport State Machine Determination AltHoldModeState sport_state = get_alt_hold_state(target_climb_rate); // State Machine switch (sport_state) { case AltHoldModeState::MotorStopped: attitude_control->reset_rate_controller_I_terms(); attitude_control->reset_yaw_target_and_rate(false); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; case AltHoldModeState::Landed_Ground_Idle: attitude_control->reset_yaw_target_and_rate(); FALLTHROUGH; case AltHoldModeState::Landed_Pre_Takeoff: attitude_control->reset_rate_controller_I_terms_smoothly(); pos_control->relax_z_controller(0.0f); // forces throttle output to decay to zero break; case AltHoldModeState::Takeoff: // initiate take-off if (!takeoff.running()) { takeoff.start(constrain_float(g.pilot_takeoff_alt,0.0f,1000.0f)); } // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); // set position controller targets adjusted for pilot input takeoff.do_pilot_takeoff(target_climb_rate); break; case AltHoldModeState::Flying: motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED); // get avoidance adjusted climb rate target_climb_rate = get_avoidance_adjusted_climbrate(target_climb_rate); #if AP_RANGEFINDER_ENABLED // update the vertical offset based on the surface measurement copter.surface_tracking.update_surface_offset(); #endif // Send the commanded climb rate to the position controller pos_control->set_pos_target_z_from_climb_rate_cm(target_climb_rate); break; } // call attitude controller attitude_control->input_euler_rate_roll_pitch_yaw(target_roll_rate, target_pitch_rate, target_yaw_rate); // run the vertical position controller and set output throttle pos_control->update_z_controller(); } #endif