control_stabilize.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142
  1. #include "Sub.h"
  2. // stabilize_init - initialise stabilize controller
  3. bool Sub::stabilize_init()
  4. {
  5. // set target altitude to zero for reporting
  6. pos_control.set_alt_target(0);
  7. last_roll_s = 0;
  8. last_pitch_s = 0;
  9. last_yaw_s = ahrs.yaw_sensor;
  10. //last_input_ms = AP_HAL::millis();
  11. last_input_ms_stable = AP_HAL::millis();
  12. pitch_input_inc=0;
  13. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  14. prepare_state = Horizontal;
  15. return true;
  16. }
  17. // stabilize_run - runs the main stabilize controller
  18. // should be called at 100hz or more
  19. extern mavlink_rov_state_monitoring_t rov_message;
  20. void Sub::handle_attitude_stablize(){
  21. uint32_t tnow = AP_HAL::millis();
  22. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  23. // get pilot desired lean angles
  24. float target_roll, target_pitch, target_yaw;
  25. // Check if set_attitude_target_no_gps is valid
  26. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  27. Quaternion(
  28. set_attitude_target_no_gps.packet.q
  29. ).to_euler(
  30. target_roll,
  31. target_pitch,
  32. target_yaw
  33. );
  34. target_roll = 100 * degrees(target_roll);
  35. target_pitch = 100 * degrees(target_pitch);
  36. target_yaw = 100 * degrees(target_yaw);
  37. last_roll_s = target_roll;
  38. last_pitch_s = target_pitch;
  39. last_yaw_s = target_yaw;
  40. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  41. } else {
  42. //int32_t yaw_input= (int32_t)((float)yaw_press*100);
  43. //int32_t roll_input = 0;
  44. int32_t pitch_input = 0;
  45. if (prepare_state == Horizontal)
  46. {
  47. pitch_input = 0;
  48. target_roll = 0;
  49. last_roll_s = 0;
  50. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  51. }else if(prepare_state == Vertical)
  52. {
  53. pitch_input = 8000;
  54. target_roll = ((float)channel_yaw->get_control_in()*0.5);
  55. target_yaw = 0;
  56. }
  57. else{
  58. pitch_input = 0;
  59. }
  60. pitch_input_inc = constrain_int32(pitch_input,-9000,9000);
  61. //-------------------------------------
  62. // target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  63. if (abs(target_roll) > 300 ){
  64. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, 0, 0);
  65. last_yaw_s = ahrs.yaw_sensor;
  66. last_roll_s = ahrs.roll_sensor;
  67. last_input_ms_stable = tnow;
  68. }else if (abs(target_yaw) > 300) {
  69. // if only yaw is being controlled, don't update pitch and roll
  70. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  71. last_yaw_s = ahrs.yaw_sensor;
  72. last_input_ms_stable = tnow;
  73. } else if (tnow < last_input_ms_stable + 250) {
  74. // just brake for a few mooments so we don't bounce
  75. last_yaw_s = ahrs.yaw_sensor;
  76. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  77. } else {
  78. // Lock attitude
  79. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll_s, (float)pitch_input_inc, last_yaw_s, true);
  80. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, last_yaw, true);
  81. }//--------------------------------------------------------------------------------------------------------------
  82. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, yaw_input, true);//pitch九十度 竖直前进有可能翻车
  83. //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切换的时候会猛烈转动
  84. static int f = 0;
  85. f++;
  86. if(f>800)
  87. {
  88. //float cosruslt = sinf(radians(286)*0.5f);
  89. //gcs().send_text(MAV_SEVERITY_INFO, " stableinput %f %f,%f ",(float)last_roll_s,(float)pitch_input_inc,(float)last_yaw_s);
  90. f=0;
  91. }
  92. }
  93. }
  94. void Sub::stabilize_run()
  95. {
  96. // if not armed set throttle to zero and exit immediately
  97. if (!motors.armed()) {
  98. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  99. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  100. attitude_control.relax_attitude_controllers();
  101. last_roll_s = 0;
  102. last_pitch_s = 0;
  103. last_yaw_s = ahrs.yaw_sensor;
  104. PressLevel_f =5.0;//压力分级复位
  105. PressLevel = no;
  106. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  107. pitch_input_inc=0;
  108. prepare_state = Horizontal;
  109. return;
  110. }
  111. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  112. handle_attitude_stablize();
  113. motors.set_forward(channel_forward->norm_input());
  114. motors.set_lateral(channel_lateral->norm_input());
  115. attitude_control.set_throttle_out(1.0-(float)PressLevel_f*0.1, false, g.throttle_filt);//压力分级
  116. rov_message.pressure_level = int(PressLevel);
  117. }