control_althold.cpp 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182
  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. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  35. // get pilot desired lean angles
  36. float target_roll, target_pitch, target_yaw;
  37. // Check if set_attitude_target_no_gps is valid
  38. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  39. Quaternion(
  40. set_attitude_target_no_gps.packet.q
  41. ).to_euler(
  42. target_roll,
  43. target_pitch,
  44. target_yaw
  45. );
  46. target_roll = 100 * degrees(target_roll);
  47. target_pitch = 100 * degrees(target_pitch);
  48. target_yaw = 100 * degrees(target_yaw);
  49. last_roll_s = target_roll;
  50. last_pitch_s = target_pitch;
  51. last_yaw_s = target_yaw;
  52. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  53. } else {
  54. //int32_t yaw_input= (int32_t)((float)yaw_press*100);
  55. //int32_t roll_input = 0;
  56. int32_t pitch_input = 0;
  57. if (prepare_state == Horizontal)
  58. {
  59. pitch_input = 0;
  60. target_roll = 0;
  61. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  62. }else if(prepare_state == Vertical)
  63. {
  64. pitch_input = -8000;
  65. target_roll = ((float)channel_yaw->get_control_in()*0.6);
  66. target_yaw = 0;
  67. }
  68. else{
  69. pitch_input = 0;
  70. }
  71. pitch_input_inc = constrain_int32(pitch_input,-9000,9000);
  72. //-------------------------------------
  73. // target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  74. if (abs(target_roll) > 300 ){
  75. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, 0, 0);
  76. last_yaw_s = ahrs.yaw_sensor;
  77. last_roll_s = ahrs.roll_sensor;
  78. last_input_ms_stable = tnow;
  79. }else if (abs(target_yaw) > 300) {
  80. // if only yaw is being controlled, don't update pitch and roll
  81. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  82. last_yaw_s = ahrs.yaw_sensor;
  83. last_input_ms_stable = tnow;
  84. } else if (tnow < last_input_ms_stable + 250) {
  85. // just brake for a few mooments so we don't bounce
  86. last_yaw_s = ahrs.yaw_sensor;
  87. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  88. } else {
  89. // Lock attitude
  90. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll_s, (float)pitch_input_inc, last_yaw_s, true);
  91. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, last_yaw, true);
  92. }//--------------------------------------------------------------------------------------------------------------
  93. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, yaw_input, true);//pitch九十度 竖直前进有可能翻车
  94. //attitude_control.input_euler_angle_roll_pitch_yaw_quat_control((float)roll_input, (float)pitch_input_inc, (float)yaw_input, true);//四元数控制在pitch90度时的效果与欧拉角控制在80度时相差不多, 但是在360往0的YAW切换的时候会猛烈转动
  95. static int f = 0;
  96. f++;
  97. if(f>800)
  98. {
  99. //float cosruslt = sinf(radians(286)*0.5f);
  100. //gcs().send_text(MAV_SEVERITY_INFO, " stableinput %f %f,%f ",(float)last_roll_s,(float)pitch_input_inc,(float)last_yaw_s);
  101. f=0;
  102. }
  103. }
  104. }
  105. // althold_run - runs the althold controller
  106. // should be called at 100hz or more
  107. void Sub::althold_run()
  108. {
  109. // When unarmed, disable motors and stabilization
  110. if (!motors.armed()) {
  111. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  112. // Sub vehicles do not stabilize roll/pitch/yaw when not auto-armed (i.e. on the ground, pilot has never raised throttle)
  113. attitude_control.set_throttle_out(0.5 ,true, g.throttle_filt);
  114. attitude_control.relax_attitude_controllers();
  115. pos_control.relax_alt_hold_controllers();
  116. last_roll = 0;
  117. last_pitch = 0;
  118. last_yaw = ahrs.yaw_sensor;
  119. holding_depth = false;
  120. return;
  121. }
  122. // Vehicle is armed, motors are free to run
  123. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  124. handle_attitude();
  125. pos_control.update_z_controller();
  126. // Read the output of the z controller and rotate it so it always points up
  127. Vector3f throttle_vehicle_frame = ahrs.get_rotation_body_to_ned().transposed() * Vector3f(0, 0, motors.get_throttle_in_bidirectional());
  128. // Output the Z controller + pilot input to all motors.
  129. //TODO: scale throttle with the ammount of thrusters in the given direction
  130. motors.set_throttle(0.5+throttle_vehicle_frame.z + channel_throttle->norm_input()-0.5);
  131. motors.set_forward(-throttle_vehicle_frame.x + channel_forward->norm_input());
  132. motors.set_lateral(-throttle_vehicle_frame.y + channel_lateral->norm_input());
  133. // We rotate the RC inputs to the earth frame to check if the user is giving an input that would change the depth.
  134. 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())));
  135. if (fabsf(earth_frame_rc_inputs.z) > 0.05f) { // Throttle input above 5%
  136. // reset z targets to current values
  137. holding_depth = false;
  138. pos_control.relax_alt_hold_controllers();
  139. } else { // hold z
  140. if (ap.at_surface) {
  141. pos_control.set_alt_target(g.surface_depth - 5.0f); // set target to 5cm below surface level
  142. holding_depth = true;
  143. } else if (ap.at_bottom) {
  144. pos_control.set_alt_target(inertial_nav.get_altitude() + 10.0f); // set target to 10 cm above bottom
  145. holding_depth = true;
  146. } else if (!holding_depth) {
  147. pos_control.set_target_to_stopping_point_z();
  148. holding_depth = true;
  149. }
  150. }
  151. }