UserCode.cpp 8.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433
  1. #include "Sub.h"
  2. //const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  3. extern const AP_HAL::HAL& hal;
  4. #define PI 3.141592653589793238462643383279502884
  5. extern mavlink_rov_state_monitoring_t rov_message;
  6. #ifdef USERHOOK_INIT
  7. void Sub::userhook_init()
  8. {
  9. // put your initialisation code here
  10. // this will be called once at start-up
  11. }
  12. #endif
  13. #ifdef USERHOOK_FASTLOOP
  14. void Sub::userhook_FastLoop()
  15. {
  16. // put your 100Hz code here
  17. }
  18. #endif
  19. #ifdef USERHOOK_50HZLOOP
  20. extern mavlink_rov_control_t rov_control;
  21. void Sub::userhook_50Hz()
  22. {
  23. USBL_PowerSwitch();
  24. getgain();
  25. getyaw();
  26. float v = chan_adc->voltage_average();
  27. chan_adc->set_pin(14);
  28. float temprature =0.0;
  29. if (v>2.58)
  30. {
  31. temprature = -44.017*v + 112.64;
  32. }else if(v>1.0){
  33. temprature =-28.635*v + 72.616;
  34. }else if(v>0.518){
  35. temprature =-48.078*v + 91.882;
  36. }else if(v>0.28){
  37. temprature =-90.07*v + 113.38;
  38. }else if(v>0.12){
  39. temprature = -195.98*v + 141.46;
  40. }
  41. else{
  42. temprature = 120;
  43. }
  44. rov_message.temp = temprature;
  45. }
  46. #endif
  47. #ifdef USERHOOK_MEDIUMLOOP
  48. void Sub::userhook_MediumLoop()
  49. {
  50. // put your 10Hz code here
  51. }
  52. #endif
  53. #ifdef USERHOOK_SLOWLOOP
  54. void Sub::userhook_SlowLoop()
  55. {
  56. // put your 3.3Hz code here
  57. }
  58. #endif
  59. #ifdef USERHOOK_SUPERSLOWLOOP
  60. void Sub::userhook_SuperSlowLoop()
  61. {
  62. // put your 1Hz code here
  63. }
  64. #endif
  65. void Sub::USBL_PowerSwitch(void)
  66. {
  67. uint32_t tnow = AP_HAL::millis();
  68. RC_Channel* chan = RC_Channels::rc_channel(8);
  69. uint16_t min = chan->get_radio_min();
  70. uint16_t max = chan->get_radio_max();
  71. if(!motors.armed()){
  72. lights1 = constrain_float(min, min, max);
  73. }
  74. if (lights1>1000)
  75. {
  76. lights = 1;
  77. }else{
  78. lights =0;
  79. }
  80. RC_Channels::set_override(8, lights1, tnow);
  81. if(motors.armed() && (rov_control.USBL_flag==1 || usblpoweroff == 1))
  82. {
  83. RC_Channels::set_override(9, 20000, tnow); // lights 2
  84. }else{
  85. RC_Channels::set_override(9, 0, tnow); // lights 1
  86. }
  87. }
  88. extern mavlink_rov_state_monitoring_t rov_message;
  89. void Sub::getgain(void){
  90. //上位机设置油门
  91. //uint16_t _gain = SRV_Channels::srv_channel(9)->get_output_min();//上位机设置油门
  92. gain = 1.0;
  93. static int j = 0;
  94. j++;
  95. if(j>800)
  96. {
  97. //gcs().send_text(MAV_SEVERITY_WARNING, " gain %f\n",(float)gain);
  98. j=0;
  99. }
  100. }
  101. void Sub::getyaw(void){
  102. if (!motors.armed()){
  103. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  104. return;
  105. }else{
  106. }
  107. }
  108. float Sub::getgainf(float data){
  109. float temp =0;
  110. if (data>=-0.6 && data <-0.08)
  111. {
  112. temp = -0.2;
  113. }else if(data>=-0.8 && data<-0.6 )
  114. {
  115. temp = -0.5;
  116. }else if(data>=-1.0 && data<-0.8 )
  117. {
  118. temp = -0.8;
  119. }
  120. else if (data<=0.6 && data >0.08)
  121. {
  122. temp = 0.2;
  123. }else if(data<=0.8 && data>0.6 )
  124. {
  125. temp = 0.5;
  126. }else if(data<=1.0 && data>0.8 )
  127. {
  128. temp = 0.8;
  129. }else{
  130. temp = 0.0;
  131. }
  132. return temp;
  133. }
  134. float Sub::sign_in(float f){
  135. return (f<0)? -1 :1;
  136. }
  137. float Sub::gaindelay(float gain1){
  138. if(throttle_continuous(gain1)){
  139. bool vel_stationary = velocity_z_filer > -5.0 && velocity_z_filer < 5.0;//cm
  140. float result = (updowmgain-0.5)*2;
  141. if (vel_stationary){
  142. last_continuous = 1;
  143. continuous_count++;
  144. if (continuous_count>=MAIN_LOOP_RATE && continuous_count<=4*MAIN_LOOP_RATE){
  145. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  146. result = constrain_float(result,-1.0,1.0);
  147. }else if(continuous_count>4*MAIN_LOOP_RATE){
  148. result = result +sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  149. result = constrain_float(result,-1.0,1.0);
  150. continuous_count = 4*MAIN_LOOP_RATE+1;
  151. }
  152. }else{
  153. if (last_continuous == 1)
  154. {
  155. if (continuous_countdec<MAIN_LOOP_RATE){
  156. continuous_countdec++;
  157. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  158. result = constrain_float(result,-1.0,1.0);
  159. }else{
  160. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  161. result = constrain_float(result,-1.0,1.0);
  162. }
  163. }else{
  164. result = (updowmgain-0.5)*2;
  165. continuous_count = 0;
  166. last_continuous = 0;
  167. continuous_countdec = 0;
  168. }
  169. }
  170. static uint16_t count = 0;
  171. count++;
  172. if (count>400)
  173. {
  174. count = 0;
  175. gcs().send_text(MAV_SEVERITY_INFO, "conti %d %d %d \n",(int)continuous_count,(int)last_continuous,(int)continuous_countdec);
  176. }
  177. return constrain_float(result/2.0+0.5,0.0,1.0);
  178. }else{
  179. continuous_count = 0;
  180. last_continuous = 0;
  181. continuous_countdec = 0;
  182. return gain1;//有压力分级的时候返回压力分级 没有压力分级的时候返回按键
  183. }
  184. }
  185. bool Sub::throttle_continuous(float gain1){
  186. static float last_gain = updowmgain;
  187. if (fabsf(gain1 -0.5)<0.05)//没有压力分级
  188. {
  189. delaygain++;
  190. if (delaygain>400)//1秒
  191. {
  192. delaygain=401;
  193. updowmgain = 0.5;
  194. last_gain = updowmgain;
  195. return FALSE;//1秒内没有持续按键
  196. }else{
  197. if ((last_gain>0.5 && updowmgain<0.5) || (last_gain<0.5 && updowmgain>0.5))//防止突然反向
  198. {
  199. last_gain = updowmgain;
  200. return FALSE;
  201. }
  202. last_gain = updowmgain;
  203. return TRUE;//持续按键
  204. }
  205. }else{
  206. delaygain=401;
  207. //有压力分级
  208. updowmgain = 0.5;
  209. last_gain = updowmgain;
  210. continuous_count = 0;
  211. last_continuous = 0;
  212. continuous_countdec = 0;
  213. return FALSE;//1秒内没有持续按键
  214. }
  215. }
  216. /*float Sub::gaindelay(float gain1){
  217. float result=0.5;
  218. static uint16_t count=0;
  219. static uint16_t countdec=0;
  220. static uint8_t last = 0;
  221. if (fabsf(gain1 -0.5)<0.05)
  222. {
  223. delaygain++;
  224. if (delaygain>300)//1秒
  225. {
  226. delaygain=0;
  227. result = 0.5;
  228. updowmgain = 0.5;
  229. count = 0;
  230. }else{
  231. float velocity_z = pos_control.alt_rate.get()/100;// m/s
  232. bool vel_stationary = velocity_z > -0.05 && velocity_z < 0.05;
  233. if (vel_stationary && updowmgain>0.5)//上升
  234. {
  235. last = 1;
  236. countdec = 0;
  237. count++;
  238. if (count<MAIN_LOOP_RATE)
  239. {
  240. result = updowmgain;
  241. }
  242. else if (count>=MAIN_LOOP_RATE && count<=3*MAIN_LOOP_RATE)
  243. {
  244. result = updowmgain+0.1*(count/MAIN_LOOP_RATE);
  245. result = constrain_float(result,-1.0,1.0);
  246. }else if(count>3*MAIN_LOOP_RATE){
  247. result = 1.0;
  248. count = 3*MAIN_LOOP_RATE+1;
  249. }
  250. }else{
  251. if (last == 1)
  252. {
  253. if (countdec<MAIN_LOOP_RATE){
  254. countdec++;
  255. result = updowmgain+0.1*(count/MAIN_LOOP_RATE);
  256. result = constrain_float(result,-1.0,1.0);
  257. }else{
  258. last = 0;
  259. result = updowmgain;
  260. count = 0;
  261. countdec = 0;
  262. }
  263. }else{
  264. result = updowmgain;
  265. count = 0;
  266. last = 0;
  267. countdec = 0;
  268. }
  269. }
  270. }
  271. return result;
  272. }else{
  273. count = 0;
  274. updowmgain = 0.5;
  275. last = 0;
  276. countdec = 0;
  277. return gain1;//有压力分级的时候返回压力分级 没有压力分级的时候返回按键
  278. }
  279. }*/
  280. //得到手柄的轴
  281. void Sub::get_heading_to_ned(Matrix3f &mat_half,Matrix3f mat_body){
  282. // Matrix3f mat_body = ahrs.get_rotation_body_to_ned();
  283. float beta = 0.0;
  284. float dot=0.0;
  285. if(mat_body.c.x<0.98 && mat_body.c.x>-0.98){//大约78.5度认为Z轴指向方向,小于78.5进入X轴指向方向
  286. Vector3f Xbx = mat_body*Vector3f(1,0,0);
  287. Xbx.z = 0.0;
  288. Vector3f Xex = Vector3f(1,0,0);
  289. dot = Xbx * Xex/Xbx.length();
  290. beta = acosf(dot );
  291. if (Xbx.y<0)
  292. {
  293. beta = -beta;
  294. }
  295. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  296. Vector3f Xez = Vector3f(0,0,1);
  297. float dotz = Xbz * Xez/Xbz.length();
  298. if (dotz<0)
  299. {
  300. beta = beta-PI;
  301. if (beta<-PI)
  302. {
  303. beta = beta+2*PI;
  304. }
  305. }
  306. mat_half.a.x= cosf(beta);
  307. mat_half.a.y=-sinf(beta);
  308. mat_half.a.z=0.0;
  309. mat_half.b.x= sinf(beta);
  310. mat_half.b.y= cosf(beta);
  311. mat_half.b.z=0.0;
  312. mat_half.c.x= 0.0;
  313. mat_half.c.y= 0.0;
  314. mat_half.c.z=1.0;
  315. }
  316. else{
  317. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  318. Xbz.z = 0.0;
  319. Vector3f Xex = Vector3f(1,0,0);
  320. dot = Xbz * Xex/Xbz.length();
  321. beta = acosf(dot );
  322. if (Xbz.y<0)
  323. {
  324. beta = -beta;
  325. }
  326. if (mat_body.c.x>0)//头朝下
  327. {
  328. beta = beta-PI;
  329. if (beta<-PI)
  330. {
  331. beta = beta+2*PI;
  332. }
  333. }
  334. mat_half.a.x= cosf(beta);
  335. mat_half.a.y=-sinf(beta);
  336. mat_half.a.z=0.0;
  337. mat_half.b.x= sinf(beta);
  338. mat_half.b.y= cosf(beta);
  339. mat_half.b.z=0.0;
  340. mat_half.c.x= 0.0;
  341. mat_half.c.y= 0.0;
  342. mat_half.c.z=1.0;
  343. }
  344. static uint16_t countx = 0;
  345. countx++;
  346. if (countx>400)
  347. {
  348. countx = 0;
  349. // gcs().send_text(MAV_SEVERITY_INFO, "ang %d %d \n",(int)(beta*180/PI),(int)ahrs.yaw_sensor/100);
  350. }
  351. }
  352. float Sub::get_pitch_to_ned(Matrix3f mat_body){
  353. float pitch_ang = acosf(mat_body.c.x);
  354. if (mat_body.c.z<0)
  355. {
  356. pitch_ang = -pitch_ang;
  357. }
  358. pitch_ang =pitch_ang-PI/2;
  359. if (pitch_ang<-PI)
  360. {
  361. pitch_ang =pitch_ang+2*PI;
  362. }
  363. return pitch_ang;
  364. }