control_stabilize.cpp 1.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657
  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::stabilize_run()
  26. {
  27. // if not armed set throttle to zero and exit immediately
  28. if (!motors.armed()) {
  29. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  30. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  31. attitude_control.relax_attitude_controllers();
  32. last_roll_s = 0;
  33. last_pitch_s = 0;
  34. last_yaw_s = ahrs.yaw_sensor;
  35. PressLevel_f =5.0;//压力分级复位
  36. PressLevel = no;
  37. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  38. pitch_input_inc=0;
  39. prepare_state = Horizontal;
  40. return;
  41. }
  42. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  43. handle_attitude();
  44. motors.set_forward(channel_forward->norm_input());
  45. motors.set_lateral(0.0);
  46. attitude_control.set_throttle_out(1.0-(float)PressLevel_f*0.1, false, g.throttle_filt);//压力分级
  47. rov_message.pressure_level = int(PressLevel);
  48. }