UserCode.cpp 3.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206
  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. RC_Channel* chan = RC_Channels::rc_channel(8);
  68. uint16_t min = chan->get_radio_min();
  69. uint16_t max = chan->get_radio_max();
  70. static uint8_t last_light = 0;
  71. if (rov_control.floodlight == 1 && motors.armed())
  72. {
  73. last_light = 1;
  74. lights1 = constrain_float(max, min, max);
  75. }
  76. else if(!motors.armed()){
  77. last_light = 0;
  78. lights1 = constrain_float(min, min, max);
  79. }else if(last_light == 1){
  80. last_light = 0;
  81. lights1 = constrain_float(min, min, max);
  82. }
  83. RC_Channels::set_override(8, lights1, tnow);
  84. if(motors.armed() && (rov_control.USBL_flag==1 || usblpoweroff == 1))
  85. {
  86. RC_Channels::set_override(9, 20000, tnow); // lights 2
  87. }else{
  88. RC_Channels::set_override(9, 0, tnow); // lights 1
  89. }
  90. }
  91. extern mavlink_rov_state_monitoring_t rov_message;
  92. void Sub::getgain(void){
  93. //上位机设置油门
  94. //uint16_t _gain = SRV_Channels::srv_channel(9)->get_output_min();//上位机设置油门
  95. gain = 1.0;
  96. static int j = 0;
  97. j++;
  98. if(j>800)
  99. {
  100. //gcs().send_text(MAV_SEVERITY_WARNING, " gain %f\n",(float)gain);
  101. j=0;
  102. }
  103. }
  104. void Sub::getyaw(void){
  105. if (!motors.armed()){
  106. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  107. return;
  108. }else{
  109. }
  110. }
  111. float Sub::getgainf(float data){
  112. float temp =0;
  113. /* if (data >0.0)
  114. {
  115. temp = sqrtf(data);
  116. }
  117. else if(data<0.0){
  118. temp = -sqrtf(-data);
  119. }
  120. else{
  121. temp = 0.0;
  122. }
  123. if (temp>0.3)
  124. {
  125. temp = constrain_float(temp,0.4,1.0);
  126. }else if(temp<-0.3){
  127. temp = constrain_float(temp,-1.0,-0.4);
  128. }else{
  129. temp=0.0;
  130. }*/
  131. if (data>=-0.6 && data <-0.08)
  132. {
  133. temp = -0.3;
  134. }else if(data>=-0.8 && data<-0.6 )
  135. {
  136. temp = -0.5;
  137. }else if(data>=-1.0 && data<-0.8 )
  138. {
  139. temp = -0.8;
  140. }
  141. else if (data<=0.6 && data >0.08)
  142. {
  143. temp = 0.3;
  144. }else if(data<=0.8 && data>0.6 )
  145. {
  146. temp = 0.5;
  147. }else if(data<=1.0 && data>0.8 )
  148. {
  149. temp = 0.8;
  150. }else{
  151. temp = 0.0;
  152. }
  153. return temp;
  154. }
  155. float Sub::gaindelay(float gain1,float _gain){
  156. if (fabsf(gain1 -0.5)<0.05)
  157. {
  158. delaygain++;
  159. if (delaygain>400)//1秒
  160. {
  161. delaygain=0;
  162. _gain = 0.5;
  163. updowmgain = 0.5;
  164. }
  165. return _gain;
  166. }else{
  167. return gain1;
  168. }
  169. }