#include "Sub.h" /* * control_circle.pde - init and run calls for circle flight mode */ // circle_init - initialise circle controller flight mode bool Sub::circle_init(bool ignore_checks) { return false; // Not implemented // if (position_ok() || ignore_checks) { // circle_pilot_yaw_override = false; // // // initialize speeds and accelerations // pos_control.set_speed_xy(wp_nav.get_speed_xy()); // pos_control.set_accel_xy(wp_nav.get_wp_acceleration()); // pos_control.set_jerk_xy_to_default(); // pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max); // pos_control.set_accel_z(g.pilot_accel_z); // // // initialise circle controller including setting the circle center based on vehicle speed // circle_nav.init(); // // return true; // }else{ // return false; // } } // circle_run - runs the circle flight mode // should be called at 100hz or more void Sub::circle_run() { float target_yaw_rate = 0; float target_climb_rate = 0; // initialize speeds and accelerations pos_control.set_speed_xy(wp_nav.get_speed_xy()); pos_control.set_accel_xy(wp_nav.get_wp_acceleration()); pos_control.set_speed_z(-g.pilot_velocity_z_max, g.pilot_velocity_z_max); pos_control.set_accel_z(g.pilot_accel_z); // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately if (!motors.armed() || !ap.auto_armed || !motors.get_interlock()) { // To-Do: add some initialisation of position controllers motors.set_desired_spool_state(AP_Motors::DESIRED_SPIN_WHEN_ARMED); // multicopters do not stabilize roll/pitch/yaw when disarmed attitude_control.set_throttle_out_unstabilized(0,true,g.throttle_filt); pos_control.set_alt_target_to_current_alt(); return; } // process pilot inputs if (!failsafe.manual_control) { // get pilot's desired yaw rate target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()); if (!is_zero(target_yaw_rate)) { circle_pilot_yaw_override = true; } // get pilot desired climb rate target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in()); // // check for pilot requested take-off // if (ap.land_complete && target_climb_rate > 0) { // // indicate we are taking off // set_land_complete(false); // // clear i term when we're taking off // set_throttle_takeoff(); // } } // set motors to full range motors.set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED); // run circle controller circle_nav.update(); // call attitude controller if (circle_pilot_yaw_override) { attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), target_yaw_rate, get_smoothing_gain()); } else { attitude_control.input_euler_angle_roll_pitch_yaw(circle_nav.get_roll(), circle_nav.get_pitch(), circle_nav.get_yaw(),true, get_smoothing_gain()); } // adjust climb rate using rangefinder if (rangefinder_alt_ok()) { // 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); } // update altitude target and call position controller pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false); pos_control.update_z_controller(); }