control_stabilize.cpp 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145
  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. if (prev_control_mode == ALT_HOLD) {
  8. last_roll_s = ahrs.roll_sensor;
  9. last_pitch_s = ahrs.pitch_sensor;
  10. } else {
  11. last_roll_s = 0;
  12. last_pitch_s = 0;
  13. }
  14. last_yaw_s = ahrs.yaw_sensor;
  15. //last_input_ms = AP_HAL::millis();
  16. last_input_ms_stable = AP_HAL::millis();
  17. pitch_input_inc=0;
  18. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  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 yaw_input= (int32_t)((float)yaw_press*100);
  48. //int32_t roll_input = 0;
  49. int32_t pitch_input = 0;
  50. if (prepare_state == Horizontal)
  51. {
  52. pitch_input = 0;
  53. target_roll = 0;
  54. last_roll_s = 0;
  55. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  56. }else if(prepare_state == Vertical)
  57. {
  58. pitch_input = 8000;
  59. target_roll = ((float)channel_yaw->get_control_in()*0.3);
  60. target_yaw = 0;
  61. }
  62. else{
  63. pitch_input = 0;
  64. }
  65. pitch_input_inc = constrain_int32(pitch_input,-9000,9000);
  66. //-------------------------------------
  67. // target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  68. if (abs(target_roll) > 300 ){
  69. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, 0, 0);
  70. last_yaw_s = ahrs.yaw_sensor;
  71. last_roll_s = ahrs.roll_sensor;
  72. last_input_ms_stable = tnow;
  73. }else if (abs(target_yaw) > 300) {
  74. // if only yaw is being controlled, don't update pitch and roll
  75. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  76. last_yaw_s = ahrs.yaw_sensor;
  77. last_input_ms_stable = tnow;
  78. } else if (tnow < last_input_ms_stable + 250) {
  79. // just brake for a few mooments so we don't bounce
  80. last_yaw_s = ahrs.yaw_sensor;
  81. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  82. } else {
  83. // Lock attitude
  84. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll_s, (float)pitch_input_inc, last_yaw_s, true);
  85. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, last_yaw, true);
  86. }//--------------------------------------------------------------------------------------------------------------
  87. //attitude_control.input_euler_angle_roll_pitch_yaw(roll_input, (float)pitch_input_inc, yaw_input, true);//pitch九十度 竖直前进有可能翻车
  88. //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切换的时候会猛烈转动
  89. static int f = 0;
  90. f++;
  91. if(f>800)
  92. {
  93. //float cosruslt = sinf(radians(286)*0.5f);
  94. //gcs().send_text(MAV_SEVERITY_INFO, " stableinput %f %f,%f ",(float)last_roll_s,(float)pitch_input_inc,(float)last_yaw_s);
  95. f=0;
  96. }
  97. }
  98. }
  99. void Sub::stabilize_run()
  100. {
  101. // if not armed set throttle to zero and exit immediately
  102. if (!motors.armed()) {
  103. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  104. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  105. attitude_control.relax_attitude_controllers();
  106. last_roll_s = 0;
  107. last_pitch_s = 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. motors.set_forward(channel_forward->norm_input());
  119. motors.set_lateral(channel_lateral->norm_input());
  120. attitude_control.set_throttle_out(1.0-(float)PressLevel_f*0.1, false, g.throttle_filt);//压力分级
  121. rov_message.pressure_level = int(PressLevel);
  122. }