12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788 |
- #include "Sub.h"
- bool Sub::circle_init()
- {
- if (!position_ok()) {
- return false;
- }
- circle_pilot_yaw_override = false;
-
- pos_control.set_max_speed_xy(wp_nav.get_default_speed_xy());
- pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
- pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
- pos_control.set_max_accel_z(g.pilot_accel_z);
-
- circle_nav.init();
- return true;
- }
- void Sub::circle_run()
- {
- float target_yaw_rate = 0;
- float target_climb_rate = 0;
-
- pos_control.set_max_speed_xy(wp_nav.get_default_speed_xy());
- pos_control.set_max_accel_xy(wp_nav.get_wp_acceleration());
- pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
- pos_control.set_max_accel_z(g.pilot_accel_z);
-
- if (!motors.armed()) {
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
-
- attitude_control.set_throttle_out(0,true,g.throttle_filt);
- attitude_control.relax_attitude_controllers();
- pos_control.set_alt_target_to_current_alt();
- return;
- }
-
-
- target_yaw_rate = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
- if (!is_zero(target_yaw_rate)) {
- circle_pilot_yaw_override = true;
- }
-
- target_climb_rate = get_pilot_desired_climb_rate(channel_throttle->get_control_in());
-
- motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
-
- circle_nav.update();
-
-
- float lateral_out, forward_out;
- translate_circle_nav_rp(lateral_out, forward_out);
-
- motors.set_lateral(lateral_out);
- motors.set_forward(forward_out);
-
- if (circle_pilot_yaw_override) {
- attitude_control.input_euler_angle_roll_pitch_euler_rate_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_yaw_rate);
- } else {
- attitude_control.input_euler_angle_roll_pitch_yaw(channel_roll->get_control_in(), channel_pitch->get_control_in(), circle_nav.get_yaw(), true);
- }
-
- pos_control.set_alt_target_from_climb_rate(target_climb_rate, G_Dt, false);
- pos_control.update_z_controller();
- }
|