control_manual.cpp 2.6 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556
  1. #include "Sub.h"
  2. // manual_init - initialise manual controller
  3. bool Sub::manual_init()
  4. {
  5. // set target altitude to zero for reporting
  6. pos_control.set_alt_target(0);
  7. // attitude hold inputs become thrust inputs in manual mode
  8. // set to neutral to prevent chaotic behavior (esp. roll/pitch)
  9. set_neutral_controls();
  10. return true;
  11. }
  12. extern mavlink_rov_state_monitoring_t rov_message;
  13. void Sub::manual_run()
  14. {
  15. // if not armed set throttle to zero and exit immediately
  16. if (!motors.armed()) {
  17. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  18. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  19. attitude_control.relax_attitude_controllers();
  20. PressLevel_f =5.0;
  21. PressLevel = no;
  22. return;
  23. }
  24. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  25. motors.set_roll(0.0);//(channel_roll->norm_input());//左右移动改为roll
  26. motors.set_pitch((0.5-channel_throttle->norm_input())*2);//(channel_pitch->norm_input());//上升下潜改为pitch
  27. motors.set_yaw(channel_yaw->norm_input() * g.acro_yaw_p / ACRO_YAW_P);
  28. motors.set_forward(channel_forward->norm_input());
  29. motors.set_lateral(channel_lateral->norm_input());
  30. motors.set_throttle(1.0-(float)PressLevel_f*0.1);//0-0.5下压
  31. static int j = 0;
  32. j++;
  33. if(j>800)
  34. {
  35. // gcs().send_text(MAV_SEVERITY_INFO, " throttle %f\n",channel_throttle->norm_input());
  36. // gcs().send_text(MAV_SEVERITY_INFO, " yaw %f\n",channel_yaw->norm_input());
  37. // gcs().send_text(MAV_SEVERITY_INFO, " forward %f\n",channel_forward->norm_input());
  38. // gcs().send_text(MAV_SEVERITY_INFO, " lateral %f\n",channel_lateral->norm_input());
  39. // gcs().send_text(MAV_SEVERITY_INFO, " forward %d %d %d %d\n",(int16_t)channel_forward->radio_in,(int16_t)channel_forward->radio_min,(int16_t)channel_forward->radio_max,(int16_t)channel_forward->radio_trim);
  40. // gcs().send_text(MAV_SEVERITY_INFO, " lateral %d %d %d %d\n",(int16_t)channel_lateral->radio_in,(int16_t)channel_lateral->radio_min,(int16_t)channel_lateral->radio_max,(int16_t)channel_lateral->radio_trim);
  41. // gcs().send_text(MAV_SEVERITY_INFO, " throttle %d %d %d %d\n",(int16_t)channel_throttle->radio_in,(int16_t)channel_throttle->radio_min,(int16_t)channel_throttle->radio_max,(int16_t)channel_throttle->radio_trim);
  42. // gcs().send_text(MAV_SEVERITY_INFO, " yaw %d %d %d %d\n",(int16_t)channel_yaw->radio_in,(int16_t)channel_yaw->radio_min,(int16_t)channel_yaw->radio_max,(int16_t)channel_yaw->radio_trim);
  43. j=0;
  44. }
  45. rov_message.pressure_level = (int)PressLevel;
  46. }