control_stabilize.cpp 4.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179
  1. #include "Sub.h"
  2. #define PI 3.141592653589793238462643383279502884
  3. // stabilize_init - initialise stabilize controller
  4. bool Sub::stabilize_init()
  5. {
  6. // set target altitude to zero for reporting
  7. pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
  8. last_roll_s = 0;
  9. last_pitch_s = 0;
  10. updowmgain =0.5;
  11. delaygain = 401;
  12. continuous_count=0;
  13. continuous_countdec=0;
  14. last_continuous = 0;
  15. last_yaw_s = ahrs.yaw_sensor;
  16. //last_input_ms = AP_HAL::millis();
  17. last_input_ms_stable = AP_HAL::millis();
  18. pitch_input_inc=0;
  19. prepare_state = Horizontal;
  20. return true;
  21. }
  22. // stabilize_run - runs the main stabilize controller
  23. // should be called at 100hz or more
  24. extern mavlink_rov_state_monitoring_t rov_message;
  25. void Sub::handle_attitude_stablize(){
  26. uint32_t tnow = AP_HAL::millis();
  27. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  28. // get pilot desired lean angles
  29. float target_roll, target_pitch, target_yaw;
  30. // Check if set_attitude_target_no_gps is valid
  31. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  32. Quaternion(
  33. set_attitude_target_no_gps.packet.q
  34. ).to_euler(
  35. target_roll,
  36. target_pitch,
  37. target_yaw
  38. );
  39. target_roll = 100 * degrees(target_roll);
  40. target_pitch = 100 * degrees(target_pitch);
  41. target_yaw = 100 * degrees(target_yaw);
  42. last_roll_s = target_roll;
  43. last_pitch_s = target_pitch;
  44. last_yaw_s = target_yaw;
  45. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  46. } else {
  47. int32_t pitch_input = 0;
  48. if (prepare_state == Horizontal)
  49. {
  50. pitch_input = 0;
  51. target_roll = 0;
  52. last_roll_s = 0;
  53. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in()*0.4);
  54. }else if(prepare_state == Vertical)
  55. {
  56. pitch_input = 8000;
  57. //target_roll = ((float)channel_yaw->get_control_in()*0.4);
  58. target_roll = 0;
  59. target_yaw = ((float)channel_yaw->get_control_in()*0.4);
  60. }
  61. else{
  62. pitch_input = 0;
  63. }
  64. pitch_input_inc = constrain_int32(pitch_input,-9000,9000);
  65. //-------------------------------------
  66. if (abs(target_roll) > 300 ){
  67. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, 0, 0);
  68. last_yaw_s = ahrs.yaw_sensor;
  69. last_roll_s = ahrs.roll_sensor;
  70. last_input_ms_stable = tnow;
  71. }else if (abs(target_yaw) > 300) {
  72. // if only yaw is being controlled, don't update pitch and roll
  73. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  74. last_yaw_s = ahrs.yaw_sensor;
  75. last_input_ms_stable = tnow;
  76. } else if (tnow < last_input_ms_stable + 250) {
  77. // just brake for a few mooments so we don't bounce
  78. last_yaw_s = ahrs.yaw_sensor;
  79. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  80. } else {
  81. // Lock attitude
  82. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll_s, (float)pitch_input_inc, last_yaw_s, true);
  83. }//--------------------------------------------------------------------------------------------------------------
  84. static int f = 0;
  85. f++;
  86. if(f>800)
  87. {
  88. //gcs().send_text(MAV_SEVERITY_INFO, " stableinput %f %f,%f ",(float)last_roll_s,(float)pitch_input_inc,(float)last_yaw_s);
  89. f=0;
  90. }
  91. }
  92. }
  93. void Sub::stabilize_run()
  94. {
  95. // if not armed set throttle to zero and exit immediately
  96. if (!motors.armed()) {
  97. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  98. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  99. attitude_control.relax_attitude_controllers();
  100. pos_control.relax_alt_hold_controllers();//目标高度为当前高度,目标速度和上次速度 当前速度
  101. last_roll_s = 0;
  102. last_pitch_s = 0;
  103. updowmgain =0.5;
  104. delaygain = 401;
  105. continuous_count=0;
  106. continuous_countdec=0;
  107. last_continuous = 0;
  108. last_yaw_s = ahrs.yaw_sensor;
  109. PressLevel_f =5.0;//压力分级复位
  110. PressLevel = no;
  111. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  112. pitch_input_inc=0;
  113. prepare_state = Horizontal;
  114. return;
  115. }
  116. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  117. handle_attitude_stablize();
  118. if(stable_alt_control){
  119. altcontrol();
  120. }
  121. else{
  122. //防止交叉
  123. float _forward = channel_forward->norm_input();
  124. float _lateral =channel_lateral->norm_input();
  125. if (fabsf(_forward)>=fabsf(_lateral))
  126. {
  127. _lateral = 0.0;
  128. }else{
  129. _forward = 0.0;
  130. }
  131. motors.set_forward(constrain_float(getgainf(_forward),-0.8,0.8));
  132. motors.set_lateral(constrain_float(getgainf(_lateral),-0.8,0.8));
  133. attitude_control.set_throttle_out(gaindelay(1.0-(float)PressLevel_f*0.1), false, g.throttle_filt);//压力分级
  134. static uint16_t count = 0;
  135. count++;
  136. if (count>400)
  137. {
  138. count = 0;
  139. gcs().send_text(MAV_SEVERITY_INFO, "set_throttle_out %f %f \n",gaindelay(1.0-(float)PressLevel_f*0.1),motors.get_throttle());
  140. }
  141. rov_message.pressure_level = int(PressLevel);
  142. }
  143. }