control_althold.cpp 5.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150
  1. #include "Sub.h"
  2. //#include "/AP_Math/AP_Math.h"
  3. /*
  4. * control_althold.pde - init and run calls for althold, flight mode
  5. */
  6. // althold_init - initialise althold controller
  7. bool Sub::althold_init()
  8. {
  9. if(!control_check_barometer()) {
  10. return false;
  11. }
  12. // initialize vertical speeds and leash lengths
  13. // sets the maximum speed up and down returned by position controller
  14. pos_control.set_max_speed_z(-get_pilot_speed_dn(), g.pilot_speed_up);
  15. pos_control.set_max_accel_z(g.pilot_accel_z);
  16. pos_control.relax_alt_hold_controllers();
  17. pos_control.set_target_to_stopping_point_z();
  18. holding_depth = true;
  19. if (prev_control_mode == STABILIZE) {
  20. last_roll_s = ahrs.roll_sensor;
  21. last_pitch_s = ahrs.pitch_sensor;
  22. } else {
  23. last_roll_s = 0;
  24. last_pitch_s = 0;
  25. }
  26. last_yaw_s = ahrs.yaw_sensor;
  27. last_input_ms = AP_HAL::millis();
  28. last_input_ms_stable = AP_HAL::millis();
  29. return true;
  30. }
  31. void Sub::handle_attitude()
  32. {
  33. uint32_t tnow = AP_HAL::millis();
  34. // get pilot desired lean angles
  35. float target_roll, target_pitch, target_yaw;
  36. // Check if set_attitude_target_no_gps is valid
  37. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  38. Quaternion(
  39. set_attitude_target_no_gps.packet.q
  40. ).to_euler(
  41. target_roll,
  42. target_pitch,
  43. target_yaw
  44. );
  45. target_roll = 100 * degrees(target_roll);
  46. target_pitch = 100 * degrees(target_pitch);
  47. target_yaw = 100 * degrees(target_yaw);
  48. last_roll = target_roll;
  49. last_pitch = target_pitch;
  50. last_yaw = target_yaw;
  51. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  52. } else {
  53. // If we don't have a mavlink attitude target, we use the pilot's input instead
  54. get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  55. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  56. if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
  57. last_roll = ahrs.roll_sensor;
  58. last_pitch = ahrs.pitch_sensor;
  59. last_yaw = ahrs.yaw_sensor;
  60. last_input_ms = tnow;
  61. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
  62. } else if (abs(target_yaw) > 300) {
  63. // if only yaw is being controlled, don't update pitch and roll
  64. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  65. last_yaw = ahrs.yaw_sensor;
  66. last_input_ms = tnow;
  67. } else if (tnow < last_input_ms + 250) {
  68. // just brake for a few mooments so we don't bounce
  69. last_yaw = ahrs.yaw_sensor;
  70. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  71. } else {
  72. // Lock attitude
  73. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
  74. }
  75. }
  76. }
  77. // althold_run - runs the althold controller
  78. // should be called at 100hz or more
  79. void Sub::althold_run()
  80. {
  81. // When unarmed, disable motors and stabilization
  82. if (!motors.armed()) {
  83. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  84. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  85. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  86. attitude_control.relax_attitude_controllers();
  87. pos_control.relax_alt_hold_controllers();
  88. last_roll = 0;
  89. last_pitch = 0;
  90. last_yaw = ahrs.yaw_sensor;
  91. holding_depth = false;
  92. return;
  93. }
  94. // Vehicle is armed, motors are free to run
  95. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  96. handle_attitude_sport();
  97. //handle_attitude();
  98. pos_control.update_z_controller();
  99. // Read the output of the z controller and rotate it so it always points up
  100. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
  101. // Output the Z controller + pilot input to all motors.
  102. //TODO: scale throttle with the ammount of thrusters in the given direction
  103. // motors.set_throttle(0.5+throttle_vehicle_frame.z + channel_throttle->norm_input()-0.5);
  104. motors.set_throttle(throttle_vehicle_frame.z + 1.0-(float)PressLevel_f*0.1);
  105. motors.set_forward(-throttle_vehicle_frame.x + channel_forward->norm_input());
  106. motors.set_lateral(-throttle_vehicle_frame.y + channel_lateral->norm_input());
  107. // We rotate the RC inputs to the earth frame to check if the user is giving an input that would change the depth.
  108. //Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0f*(-0.5f+channel_throttle->norm_input())));
  109. Vector3f earth_frame_rc_inputs = ahrs.get_rotation_body_to_ned() * Vector3f(channel_forward->norm_input(), channel_lateral->norm_input(), (2.0*(0.5-PressLevel_f*0.1)));
  110. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  111. // reset z targets to current values
  112. holding_depth = false;
  113. pos_control.relax_alt_hold_controllers();
  114. } else { // hold z
  115. if (ap.at_surface) {
  116. pos_control.set_alt_target(g.surface_depth - 5.0f); // set target to 5cm below surface level
  117. holding_depth = true;
  118. } else if (ap.at_bottom) {
  119. pos_control.set_alt_target(inertial_nav.get_altitude() + 10.0f); // set target to 10 cm above bottom
  120. holding_depth = true;
  121. } else if (!holding_depth) {
  122. pos_control.set_target_to_stopping_point_z();
  123. holding_depth = true;
  124. }
  125. }
  126. }