control_stabilize.cpp 5.0 KB

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