control_sport.cpp 4.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118
  1. #include "Sub.h"
  2. extern mavlink_rov_state_monitoring_t rov_message;
  3. // stabilize_init - initialise stabilize controller
  4. bool Sub::sport_init()
  5. {
  6. // set target altitude to zero for reporting
  7. pos_control.set_alt_target(0);
  8. if (prev_control_mode == ALT_HOLD) {
  9. last_roll = ahrs.roll_sensor;
  10. last_pitch = ahrs.pitch_sensor;
  11. } else {
  12. last_roll = 0;
  13. last_pitch = 0;
  14. }
  15. last_yaw = ahrs.yaw_sensor;
  16. pitch_input_inc=0;
  17. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  18. last_input_ms = AP_HAL::millis();
  19. return true;
  20. }
  21. // stabilize_run - runs the main stabilize controller
  22. // should be called at 100hz or more
  23. void Sub::sport_run()
  24. {
  25. // if not armed set throttle to zero and exit immediately
  26. if (!motors.armed()) {
  27. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  28. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  29. attitude_control.relax_attitude_controllers();
  30. last_roll = 0;
  31. last_pitch = 0;
  32. last_yaw = ahrs.yaw_sensor;
  33. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  34. return;
  35. }
  36. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  37. uint32_t tnow = AP_HAL::millis();
  38. // get pilot desired lean angles
  39. float target_roll, target_pitch, target_yaw;
  40. // Check if set_attitude_target_no_gps is valid
  41. if (tnow - sub.set_attitude_target_no_gps.last_message_ms < 5000) {
  42. Quaternion(
  43. set_attitude_target_no_gps.packet.q
  44. ).to_euler(
  45. target_roll,
  46. target_pitch,
  47. target_yaw
  48. );
  49. target_roll = 100 * degrees(target_roll);
  50. target_pitch = 100 * degrees(target_pitch);
  51. target_yaw = 100 * degrees(target_yaw);
  52. last_roll = target_roll;
  53. last_pitch = target_pitch;
  54. last_yaw = target_yaw;
  55. attitude_control.input_euler_angle_roll_pitch_yaw(target_roll, target_pitch, target_yaw, true);
  56. } else {
  57. // If we don't have a mavlink attitude target, we use the pilot's input instead
  58. //get_pilot_desired_lean_angles(channel_roll->get_control_in(), channel_pitch->get_control_in(), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  59. get_pilot_desired_lean_angles((int16_t)(channel_lateral->norm_input()*5700), (int16_t)((0.5-channel_throttle->norm_input())*5700*2), target_roll, target_pitch, attitude_control.get_althold_lean_angle_max());
  60. target_yaw = get_pilot_desired_yaw_rate(channel_yaw->get_control_in());
  61. if (abs(target_roll) > 300 || abs(target_pitch) > 300) {
  62. last_roll = ahrs.roll_sensor;
  63. last_pitch = ahrs.pitch_sensor;
  64. last_yaw = ahrs.yaw_sensor;
  65. last_input_ms = tnow;
  66. attitude_control.input_rate_bf_roll_pitch_yaw(target_roll, target_pitch, target_yaw);
  67. } else if (abs(target_yaw) > 300) {
  68. // if only yaw is being controlled, don't update pitch and roll
  69. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, target_yaw);
  70. last_yaw = ahrs.yaw_sensor;
  71. last_input_ms = tnow;
  72. } else if (tnow < last_input_ms + 250) {
  73. // just brake for a few mooments so we don't bounce
  74. last_yaw = ahrs.yaw_sensor;
  75. attitude_control.input_rate_bf_roll_pitch_yaw(0, 0, 0);
  76. } else {
  77. // Lock attitude
  78. attitude_control.input_euler_angle_roll_pitch_yaw(last_roll, last_pitch, last_yaw, true);
  79. }
  80. }
  81. // handle_attitude();
  82. // output pilot's throttle
  83. //attitude_control.set_throttle_out(channel_throttle->norm_input(), false, g.throttle_filt);
  84. attitude_control.set_throttle_out(1.0-(float)PressLevel_f*0.1, false, g.throttle_filt);//压力分级
  85. rov_message.pressure_level = int(PressLevel);
  86. //control_in is range -1000-1000
  87. //radio_in is raw pwm value
  88. motors.set_forward(channel_forward->norm_input());
  89. //motors.set_lateral(channel_lateral->norm_input());
  90. motors.set_lateral(0);
  91. static int j = 0;
  92. j++;
  93. if(j>800)
  94. {
  95. //gcs().send_text(MAV_SEVERITY_INFO, " roll p y %d %d %d\n",(int16_t)(channel_lateral->norm_input()*5700),(int16_t)((0.5-channel_throttle->norm_input())*5700*2),channel_yaw->get_control_in());
  96. //gcs().send_text(MAV_SEVERITY_INFO, " throttle forward lateral %f %f %f \n",(float)PressLevel_f*0.1,channel_forward->norm_input());
  97. //gcs().send_text(MAV_SEVERITY_INFO, " channel_roll p y %d %d %d\n",channel_roll->get_control_in(),channel_pitch->get_control_in(),channel_yaw->get_control_in());
  98. //gcs().send_text(MAV_SEVERITY_INFO, " throttle forward lateral %f %f %f \n",channel_throttle->norm_input(),channel_forward->norm_input(),channel_lateral->norm_input());
  99. j=0;
  100. }
  101. }