UserCode.cpp 2.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. #include "Sub.h"
  2. //const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  3. extern const AP_HAL::HAL& hal;
  4. extern mavlink_rov_state_monitoring_t rov_message;
  5. #ifdef USERHOOK_INIT
  6. void Sub::userhook_init()
  7. {
  8. // put your initialisation code here
  9. // this will be called once at start-up
  10. }
  11. #endif
  12. #ifdef USERHOOK_FASTLOOP
  13. void Sub::userhook_FastLoop()
  14. {
  15. // put your 100Hz code here
  16. }
  17. #endif
  18. #ifdef USERHOOK_50HZLOOP
  19. extern mavlink_rov_control_t rov_control;
  20. void Sub::userhook_50Hz()
  21. {
  22. USBL_PowerSwitch();
  23. getgain();
  24. getyaw();
  25. float v = chan_adc->voltage_average();
  26. chan_adc->set_pin(14);
  27. float temprature =0.0;
  28. if (v>2.58)
  29. {
  30. temprature = -44.017*v + 112.64;
  31. }else if(v>1.0){
  32. temprature =-28.635*v + 72.616;
  33. }else if(v>0.518){
  34. temprature =-48.078*v + 91.882;
  35. }else if(v>0.28){
  36. temprature =-90.07*v + 113.38;
  37. }else if(v>0.12){
  38. temprature = -195.98*v + 141.46;
  39. }
  40. else{
  41. temprature = 120;
  42. }
  43. rov_message.temp = temprature;
  44. }
  45. #endif
  46. #ifdef USERHOOK_MEDIUMLOOP
  47. void Sub::userhook_MediumLoop()
  48. {
  49. // put your 10Hz code here
  50. }
  51. #endif
  52. #ifdef USERHOOK_SLOWLOOP
  53. void Sub::userhook_SlowLoop()
  54. {
  55. // put your 3.3Hz code here
  56. }
  57. #endif
  58. #ifdef USERHOOK_SUPERSLOWLOOP
  59. void Sub::userhook_SuperSlowLoop()
  60. {
  61. // put your 1Hz code here
  62. }
  63. #endif
  64. void Sub::USBL_PowerSwitch(void)
  65. {
  66. uint32_t tnow = AP_HAL::millis();
  67. if (rov_control.floodlight == 1 && motors.armed())
  68. {
  69. RC_Channels::set_override(8, 20000, tnow); // lights 1
  70. }
  71. else {
  72. RC_Channels::set_override(8, 0, tnow); // lights 1
  73. }
  74. if(motors.armed() && (rov_control.USBL_flag==1 || usblpoweroff == 1))
  75. {
  76. RC_Channels::set_override(9, 20000, tnow); // lights 2
  77. }else{
  78. RC_Channels::set_override(9, 0, tnow); // lights 1
  79. }
  80. }
  81. extern mavlink_rov_state_monitoring_t rov_message;
  82. void Sub::getgain(void){
  83. //上位机设置油门
  84. //uint16_t _gain = SRV_Channels::srv_channel(9)->get_output_min();//上位机设置油门
  85. gain = 1.0;
  86. static int j = 0;
  87. j++;
  88. if(j>800)
  89. {
  90. //gcs().send_text(MAV_SEVERITY_WARNING, " gain %f\n",(float)gain);
  91. j=0;
  92. }
  93. }
  94. void Sub::getyaw(void){
  95. if (!motors.armed()){
  96. yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  97. return;
  98. }else{
  99. }
  100. }