UserCode.cpp 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741
  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. //read_external_DVL(hal.uartD);//uart4
  51. //write_external_DVL(hal.uartD);
  52. }
  53. #endif
  54. #ifdef USERHOOK_SLOWLOOP
  55. void Sub::userhook_SlowLoop()
  56. {
  57. // put your 3.3Hz code here
  58. }
  59. #endif
  60. #ifdef USERHOOK_SUPERSLOWLOOP
  61. void Sub::userhook_SuperSlowLoop()
  62. {
  63. // put your 1Hz code here
  64. }
  65. #endif
  66. void Sub::USBL_PowerSwitch(void)
  67. {
  68. uint32_t tnow = AP_HAL::millis();
  69. RC_Channel* chan = RC_Channels::rc_channel(8);
  70. uint16_t min = chan->get_radio_min();
  71. uint16_t max = chan->get_radio_max();
  72. if(!motors.armed()){
  73. lights1 = constrain_float(min, min, max);
  74. }
  75. if (lights1>1000)
  76. {
  77. lights = 1;
  78. }else{
  79. lights =0;
  80. }
  81. RC_Channels::set_override(8, lights1, tnow);
  82. if(motors.armed() && (rov_control.USBL_flag==1 || usblpoweroff == 1))
  83. {
  84. RC_Channels::set_override(9, 20000, tnow); // lights 2
  85. }else{
  86. RC_Channels::set_override(9, 0, tnow); // lights 1
  87. }
  88. }
  89. extern mavlink_rov_state_monitoring_t rov_message;
  90. void Sub::getgain(void){
  91. //上位机设置油门
  92. //uint16_t _gain = SRV_Channels::srv_channel(9)->get_output_min();//上位机设置油门
  93. gain = 1.0;
  94. static int j = 0;
  95. j++;
  96. if(j>800)
  97. {
  98. //gcs().send_text(MAV_SEVERITY_WARNING, " gain %f\n",(float)gain);
  99. j=0;
  100. }
  101. }
  102. void Sub::getyaw(void){
  103. if (!motors.armed()){
  104. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  105. return;
  106. }else{
  107. }
  108. }
  109. float Sub::getgainf(float data){
  110. float temp =0;
  111. if (data>=-0.6 && data <-0.08)
  112. {
  113. temp = -0.2;
  114. }else if(data>=-0.8 && data<-0.6 )
  115. {
  116. temp = -0.5;
  117. }else if(data>=-1.0 && data<-0.8 )
  118. {
  119. temp = -0.8;
  120. }
  121. else if (data<=0.6 && data >0.08)
  122. {
  123. temp = 0.2;
  124. }else if(data<=0.8 && data>0.6 )
  125. {
  126. temp = 0.5;
  127. }else if(data<=1.0 && data>0.8 )
  128. {
  129. temp = 0.8;
  130. }else{
  131. temp = 0.0;
  132. }
  133. return temp;
  134. }
  135. float Sub::getgainfstatble(float data){
  136. float temp =0;
  137. if (data>=-0.5 && data <-0.08)
  138. {
  139. temp = -0.2;
  140. }else if(data>=-0.8 && data<-0.5 )
  141. {
  142. temp = -0.5;
  143. }else if(data>=-1.0 && data<-0.8 )
  144. {
  145. temp = -1.0;
  146. }
  147. else if (data<=0.5 && data >0.08)
  148. {
  149. temp = 0.2;
  150. }else if(data<=0.8 && data>0.5 )
  151. {
  152. temp = 0.5;
  153. }else if(data<=1.0 && data>0.8 )
  154. {
  155. temp = 1.0;
  156. }else{
  157. temp = 0.0;
  158. }
  159. return temp;
  160. }
  161. float Sub::sign_in(float f){
  162. return (f<0)? -1 :1;
  163. }
  164. float Sub::gaindelay(float gain1){
  165. if(throttle_continuous(gain1)){
  166. bool vel_stationary = velocity_z_filer > -5.0 && velocity_z_filer < 5.0;//cm
  167. float result = (updowmgain-0.5)*2;
  168. if (vel_stationary){
  169. last_continuous = 1;
  170. continuous_count++;
  171. if (continuous_count>=MAIN_LOOP_RATE && continuous_count<=4*MAIN_LOOP_RATE){
  172. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  173. result = constrain_float(result,-1.0,1.0);
  174. }else if(continuous_count>4*MAIN_LOOP_RATE){
  175. result = result +sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  176. result = constrain_float(result,-1.0,1.0);
  177. continuous_count = 4*MAIN_LOOP_RATE+1;
  178. }
  179. }else{
  180. if (last_continuous == 1)
  181. {
  182. if (continuous_countdec<MAIN_LOOP_RATE){
  183. continuous_countdec++;
  184. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  185. result = constrain_float(result,-1.0,1.0);
  186. }else{
  187. result = result + sign_in(result)*0.2*(continuous_count/MAIN_LOOP_RATE);//步长是0.2
  188. result = constrain_float(result,-1.0,1.0);
  189. }
  190. }else{
  191. result = (updowmgain-0.5)*2;
  192. continuous_count = 0;
  193. last_continuous = 0;
  194. continuous_countdec = 0;
  195. }
  196. }
  197. static uint16_t count = 0;
  198. count++;
  199. if (count>400)
  200. {
  201. count = 0;
  202. gcs().send_text(MAV_SEVERITY_INFO, "conti %d %d %d %f\n",(int)continuous_count,(int)last_continuous,(int)continuous_countdec,result);
  203. }
  204. return constrain_float(result/2.0+0.5,0.0,1.0);
  205. }else{
  206. continuous_count = 0;
  207. last_continuous = 0;
  208. continuous_countdec = 0;
  209. return gain1;//有压力分级的时候返回压力分级 没有压力分级的时候返回按键
  210. }
  211. }
  212. bool Sub::throttle_continuous(float gain1){
  213. static float last_gain = updowmgain;
  214. if (fabsf(gain1 -0.5)<0.05)//没有压力分级
  215. {
  216. delaygain++;
  217. if (delaygain>400)//1秒
  218. {
  219. delaygain=401;
  220. updowmgain = 0.5;
  221. last_gain = updowmgain;
  222. return FALSE;//1秒内没有持续按键
  223. }else{
  224. if ((last_gain>0.5 && updowmgain<0.5) || (last_gain<0.5 && updowmgain>0.5))//防止突然反向
  225. {
  226. last_gain = updowmgain;
  227. return FALSE;
  228. }
  229. last_gain = updowmgain;
  230. return TRUE;//持续按键
  231. }
  232. }else{
  233. delaygain=401;
  234. //有压力分级
  235. updowmgain = 0.5;
  236. last_gain = updowmgain;
  237. continuous_count = 0;
  238. last_continuous = 0;
  239. continuous_countdec = 0;
  240. return FALSE;//1秒内没有持续按键
  241. }
  242. }
  243. /*float Sub::gaindelay(float gain1){
  244. float result=0.5;
  245. static uint16_t count=0;
  246. static uint16_t countdec=0;
  247. static uint8_t last = 0;
  248. if (fabsf(gain1 -0.5)<0.05)
  249. {
  250. delaygain++;
  251. if (delaygain>300)//1秒
  252. {
  253. delaygain=0;
  254. result = 0.5;
  255. updowmgain = 0.5;
  256. count = 0;
  257. }else{
  258. float velocity_z = pos_control.alt_rate.get()/100;// m/s
  259. bool vel_stationary = velocity_z > -0.05 && velocity_z < 0.05;
  260. if (vel_stationary && updowmgain>0.5)//上升
  261. {
  262. last = 1;
  263. countdec = 0;
  264. count++;
  265. if (count<MAIN_LOOP_RATE)
  266. {
  267. result = updowmgain;
  268. }
  269. else if (count>=MAIN_LOOP_RATE && count<=3*MAIN_LOOP_RATE)
  270. {
  271. result = updowmgain+0.1*(count/MAIN_LOOP_RATE);
  272. result = constrain_float(result,-1.0,1.0);
  273. }else if(count>3*MAIN_LOOP_RATE){
  274. result = 1.0;
  275. count = 3*MAIN_LOOP_RATE+1;
  276. }
  277. }else{
  278. if (last == 1)
  279. {
  280. if (countdec<MAIN_LOOP_RATE){
  281. countdec++;
  282. result = updowmgain+0.1*(count/MAIN_LOOP_RATE);
  283. result = constrain_float(result,-1.0,1.0);
  284. }else{
  285. last = 0;
  286. result = updowmgain;
  287. count = 0;
  288. countdec = 0;
  289. }
  290. }else{
  291. result = updowmgain;
  292. count = 0;
  293. last = 0;
  294. countdec = 0;
  295. }
  296. }
  297. }
  298. return result;
  299. }else{
  300. count = 0;
  301. updowmgain = 0.5;
  302. last = 0;
  303. countdec = 0;
  304. return gain1;//有压力分级的时候返回压力分级 没有压力分级的时候返回按键
  305. }
  306. }*/
  307. //得到手柄的轴
  308. void Sub::get_heading_to_ned(Matrix3f &mat_half,Matrix3f mat_body){
  309. // Matrix3f mat_body = ahrs.get_rotation_body_to_ned();
  310. float beta = 0.0;
  311. float dot=0.0;
  312. if(mat_body.c.x<0.98 && mat_body.c.x>-0.98){//大约78.5度认为Z轴指向方向,小于78.5进入X轴指向方向
  313. Vector3f Xbx = mat_body*Vector3f(1,0,0);
  314. Xbx.z = 0.0;
  315. Vector3f Xex = Vector3f(1,0,0);
  316. dot = Xbx * Xex/Xbx.length();
  317. beta = acosf(dot );
  318. if (Xbx.y<0)
  319. {
  320. beta = -beta;
  321. }
  322. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  323. Vector3f Xez = Vector3f(0,0,1);
  324. float dotz = Xbz * Xez/Xbz.length();
  325. if (dotz<0)
  326. {
  327. beta = beta-PI;
  328. if (beta<-PI)
  329. {
  330. beta = beta+2*PI;
  331. }
  332. }
  333. mat_half.a.x= cosf(beta);
  334. mat_half.a.y=-sinf(beta);
  335. mat_half.a.z=0.0;
  336. mat_half.b.x= sinf(beta);
  337. mat_half.b.y= cosf(beta);
  338. mat_half.b.z=0.0;
  339. mat_half.c.x= 0.0;
  340. mat_half.c.y= 0.0;
  341. mat_half.c.z=1.0;
  342. }
  343. else{
  344. Vector3f Xbz = mat_body*Vector3f(0,0,1);
  345. Xbz.z = 0.0;
  346. Vector3f Xex = Vector3f(1,0,0);
  347. dot = Xbz * Xex/Xbz.length();
  348. beta = acosf(dot );
  349. if (Xbz.y<0)
  350. {
  351. beta = -beta;
  352. }
  353. if (mat_body.c.x>0)//头朝下
  354. {
  355. beta = beta-PI;
  356. if (beta<-PI)
  357. {
  358. beta = beta+2*PI;
  359. }
  360. }
  361. mat_half.a.x= cosf(beta);
  362. mat_half.a.y=-sinf(beta);
  363. mat_half.a.z=0.0;
  364. mat_half.b.x= sinf(beta);
  365. mat_half.b.y= cosf(beta);
  366. mat_half.b.z=0.0;
  367. mat_half.c.x= 0.0;
  368. mat_half.c.y= 0.0;
  369. mat_half.c.z=1.0;
  370. }
  371. static uint16_t countx = 0;
  372. countx++;
  373. if (countx>400)
  374. {
  375. countx = 0;
  376. // gcs().send_text(MAV_SEVERITY_INFO, "ang %d %d \n",(int)(beta*180/PI),(int)ahrs.yaw_sensor/100);
  377. }
  378. }
  379. float Sub::get_pitch_to_ned(Matrix3f mat_body){
  380. float pitch_ang = acosf(mat_body.c.x);
  381. if (mat_body.c.z<0)
  382. {
  383. pitch_ang = -pitch_ang;
  384. }
  385. pitch_ang =pitch_ang-PI/2;
  386. if (pitch_ang<-PI)
  387. {
  388. pitch_ang =pitch_ang+2*PI;
  389. }
  390. return pitch_ang;
  391. }
  392. void Sub::charArrtobyteArr(unsigned char *charArr ,uint8_t * dec,int16_t len){
  393. int16_t i = 0;
  394. for(i = 0 ;i<len;i++){
  395. dec[i] = (uint8_t)charArr[i] ;
  396. }
  397. }
  398. void Sub::charArrtodecArr(unsigned char *charArr ,uint8_t * dec,int16_t len){
  399. int16_t i = 0;
  400. uint8_t j=0;
  401. uint8_t k=0;
  402. char charArrtemp[20]={0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
  403. static uint8_t cnt = 0;
  404. cnt = 0;
  405. int typeflag = 0;
  406. for(i = 4 ;i<len;i++){
  407. if (charArr[i]!=',' && charArr[i]!=';'&& charArr[i]!='*')//&&charArr[i]!='y'&&charArr[i]!='n')//分割数据
  408. {
  409. charArrtemp[cnt++] = charArr[i];
  410. if (charArr[i] == '.')//不是整形
  411. {
  412. typeflag = 1;
  413. }
  414. }else{
  415. charArrtemp[cnt] = '\0';
  416. if (charArr[i-1]=='y' ||charArr[i-1]=='n')
  417. {
  418. arryf[j++] = charArr[i-1];
  419. }
  420. else if(typeflag == 0 && cnt>11)//长长整型 只有时间戳才会有这样的长整形
  421. {
  422. int64_t l = atoll (charArrtemp);
  423. timearry[k++] = l;
  424. }else if(cnt>11){//双精度 转换的话会丢掉精度 因此变成整形不会丢失精度
  425. int il, jl,kl=0;
  426. for (il = 0, jl = 0; charArrtemp[il] != '\0'; il++) {
  427. if (charArrtemp[il] != '.') {
  428. charArrtemp[jl++] = charArrtemp[il];
  429. }else{
  430. kl = il;//找出.的位置
  431. }
  432. }
  433. charArrtemp[jl] = '\0';
  434. DVLdata_wrp.time_Mulfactor = jl-kl;
  435. int64_t l = atoll (charArrtemp);
  436. timearry[2] = l;
  437. //gcs().send_text(MAV_SEVERITY_INFO, "kl %02x %lld",DVLdata_wrp.time_Mulfactor,timearry[2]);
  438. }
  439. else{
  440. float f = atof(charArrtemp);
  441. arryf[j++] = f;
  442. }
  443. memset(charArrtemp, 0, sizeof(unsigned char)*20);
  444. cnt = 0;
  445. typeflag = 0;
  446. }
  447. }
  448. }
  449. void Sub:: write_external_DVL(AP_HAL::UARTDriver *uart){
  450. if (uart == nullptr) {
  451. return;
  452. }
  453. //unsigned char send_sucess = 0;
  454. /*if (DVLSet.type == 'D')
  455. {
  456. //send_sucess = uart->write(DVLSet.data,DVLSet.len);
  457. uart->write(DVLSet.data,DVLSet.len);
  458. DVLSet.type = '0';
  459. }*/
  460. static int jsn = 0;
  461. jsn++;
  462. if(jsn>100)
  463. {
  464. // gcs().send_text(MAV_SEVERITY_INFO, " send %c%c%c%c%c%c%c%c%c%c%c\n",DVLSet.data[0],DVLSet.data[1],DVLSet.data[2],DVLSet.data[3],DVLSet.data[4],DVLSet.data[5],DVLSet.data[6],DVLSet.data[7],DVLSet.data[8],DVLSet.data[9],DVLSet.data[10]);
  465. // gcs().send_text(MAV_SEVERITY_INFO, " send %d\n",(int)send_sucess);
  466. jsn=0;
  467. }
  468. }
  469. void Sub::read_external_DVL(AP_HAL::UARTDriver *uart){
  470. if (uart == nullptr) {
  471. return;
  472. }
  473. uint32_t readtime=AP_HAL::micros();//微秒
  474. static uint32_t DVLvalidtime=AP_HAL::millis();//毫秒
  475. unsigned char received_char;
  476. static bool exitLoop = FALSE;
  477. exitLoop = FALSE;
  478. while(uart->available()&&!exitLoop)//recive num
  479. {
  480. received_char = uart->read();
  481. if (received_char == 'w')// 开始
  482. {
  483. RxDVL[0] = received_char;
  484. }
  485. if (RxDVL[0] == 'w' && received_char != '\r' && received_char != '\n')//得到开头 并且不是 尾 后开始存数据 '\r' 回车 '\n' 换行
  486. {
  487. RxDVL[DVL_RxCnt++]=received_char;//保存数据
  488. }
  489. if ((received_char == '\r') || (received_char == '\n'))//到达帧尾
  490. {
  491. if(RxDVL[0] == 'w' && RxDVL[1] == 'r'&&(RxDVL[2] == 'z'||RxDVL[2] == 'p'||RxDVL[2] == 'a'||RxDVL[2] == 'n'||RxDVL[2] == '?')){
  492. //开始校验
  493. uint8_t stringobj[DVL_RxCnt];
  494. charArrtobyteArr(RxDVL,stringobj,DVL_RxCnt);//转换成byte数组
  495. uint8_t crcsum = crc_crc8(stringobj, DVL_RxCnt-3);//使用模拟测试字符数组
  496. uint8_t dh = chartodec(RxDVL[DVL_RxCnt-2]);
  497. uint8_t dl = chartodec(RxDVL[DVL_RxCnt-1]);
  498. for (int gcsi2 = 0; gcsi2 < DVL_RxCnt/32 + 1; gcsi2++)
  499. {
  500. gcs().send_text(MAV_SEVERITY_INFO, "org %c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c%c",RxDVL[gcsi2*32+0],RxDVL[gcsi2*32+1],RxDVL[gcsi2*32+2],RxDVL[gcsi2*32+3],RxDVL[gcsi2*32+4],RxDVL[gcsi2*32+5],RxDVL[gcsi2*32+6],RxDVL[gcsi2*32+7],
  501. RxDVL[gcsi2*32+8],RxDVL[gcsi2*32+9],RxDVL[gcsi2*32+10],RxDVL[gcsi2*32+11],RxDVL[gcsi2*32+12],RxDVL[gcsi2*32+13],RxDVL[gcsi2*32+14],RxDVL[gcsi2*32+15],
  502. RxDVL[gcsi2*32+16],RxDVL[gcsi2*32+17],RxDVL[gcsi2*32+18],RxDVL[gcsi2*32+19],RxDVL[gcsi2*32+20],RxDVL[gcsi2*32+21],RxDVL[gcsi2*32+22],RxDVL[gcsi2*32+23],
  503. RxDVL[gcsi2*32+24],RxDVL[gcsi2*32+25],RxDVL[gcsi2*32+26],RxDVL[gcsi2*32+27],RxDVL[gcsi2*32+28],RxDVL[gcsi2*32+29],RxDVL[gcsi2*32+30],RxDVL[gcsi2*32+31]);
  504. }
  505. if (crcsum == dh*16+dl)
  506. {//校验通过
  507. charArrtodecArr(RxDVL,stringobj,DVL_RxCnt-2);//string 类型转为数据类型 计算数据
  508. switch (RxDVL[2]) {
  509. case 'z'://Velocity report
  510. //Velocity report wrz, [vx],[vy],[vz],[valid],[altitude],[fom],[covariance],
  511. //[time_of_validity],[time_of_transmission],[time],[status]
  512. DVLdata_wrz.Vx = arryf[0];
  513. DVLdata_wrz.Vy = arryf[1];
  514. DVLdata_wrz.Vz = arryf[2];
  515. DVLdata_wrz.valid = arryf[3];// 'y'/'n'
  516. DVLdata_wrz.altitude = arryf[4];
  517. DVLdata_wrz.fom = arryf[5];
  518. DVLdata_wrz.covariancearr[0] = arryf[6];
  519. DVLdata_wrz.covariancearr[1] = arryf[7];
  520. DVLdata_wrz.covariancearr[2] = arryf[8];
  521. DVLdata_wrz.covariancearr[3] = arryf[9];
  522. DVLdata_wrz.covariancearr[4] = arryf[10];
  523. DVLdata_wrz.covariancearr[5] = arryf[11];
  524. DVLdata_wrz.covariancearr[6] = arryf[12];
  525. DVLdata_wrz.covariancearr[7] = arryf[13];
  526. DVLdata_wrz.covariancearr[8] = arryf[14];
  527. DVLdata_wrz.timeofvalidity = timearry[0];
  528. DVLdata_wrz.timeoftransmission = timearry[1];
  529. DVLdata_wrz.time = arryf[15];
  530. DVLdata_wrz.status = (int)arryf[16];
  531. //树莓派源码中使用的是这一帧数据而不是wrp
  532. gcs().send_text(MAV_SEVERITY_INFO, "z %d %c %.3f %.3f %.3f %.3f",DVLdata_wrz.status,DVLdata_wrz.valid,DVLdata_wrz.time,DVLdata_wrz.Vx,DVLdata_wrz.Vy,DVLdata_wrz.Vz) ;
  533. gcs().send_text(MAV_SEVERITY_INFO, "z %lld %lld %.3f",DVLdata_wrz.timeofvalidity,DVLdata_wrz.timeoftransmission,DVLdata_wrz.time) ;
  534. if(DVLdata_wrz.status == 0){//0正常 1 故障
  535. //说明数据有效
  536. if (DVLdata_wrz.valid == 'y')//说明高度和速度有效
  537. {
  538. //transfer_position_delta_msg();
  539. DVLvalidtime=AP_HAL::millis();
  540. gcs().send_text(MAV_SEVERITY_INFO, "wrz %ld",DVLvalidtime) ;
  541. }
  542. }
  543. exitLoop = TRUE;//退出循环
  544. break;
  545. case 'u'://Transducer report
  546. // wru, [id],[velocity],[distance],[rssi],[nsd]
  547. DVLdata_wru.id = (int)arryf[0];
  548. DVLdata_wru.velocity = arryf[1];
  549. DVLdata_wru.distance= arryf[2];
  550. DVLdata_wru.rssi = (int)arryf[3];
  551. DVLdata_wru.nsd = (int)arryf[4];
  552. gcs().send_text(MAV_SEVERITY_INFO, "wru %d %f %f %d",DVLdata_wru.id,DVLdata_wru.velocity,DVLdata_wru.distance,DVLdata_wru.rssi) ;
  553. exitLoop = TRUE;//退出循环
  554. break;
  555. case 'p'://Dead reckoning report
  556. // wrp, [time_stamp],[x],[y],[z],[pos_std],[roll],[pitch],[yaw],[status]
  557. DVLdata_wrp.time_stamp=timearry[2];//s 不能准确得到或者说不能准确打印出来
  558. DVLdata_wrp.Dx = arryf[0];
  559. DVLdata_wrp.Dy = arryf[1];
  560. DVLdata_wrp.Dz = arryf[2];
  561. DVLdata_wrp.pos_std = arryf[3];
  562. DVLdata_wrp.roll = arryf[4];
  563. DVLdata_wrp.pitch = arryf[5];
  564. DVLdata_wrp.yaw = arryf[6];
  565. DVLdata_wrp.status = (int)arryf[7];
  566. gcs().send_text(MAV_SEVERITY_INFO, "wrp %f %f %f %f",DVLdata_wrp.Dx,DVLdata_wrp.Dy,DVLdata_wrp.Dz,DVLdata_wrp.pos_std) ;
  567. exitLoop = TRUE;//退出循环
  568. break;
  569. //Dead reckoning can be reset by issuing the wcr command. The reply will be an ack ( wra ) if
  570. //the reset is successful, and a nak ( wrn ) if not.
  571. case 'a'://下发命令反馈 Successfully
  572. /*memset(DVLreturn.data, 0, 32);
  573. DVLreturn.type = 'V';
  574. DVLreturn.len = 3;
  575. DVLreturn.data[0] = 'w';
  576. DVLreturn.data[1] = 'r';
  577. DVLreturn.data[2] = 'a';*/
  578. gcs().send_text(MAV_SEVERITY_INFO, "wra");
  579. exitLoop = TRUE;//退出循环
  580. break;
  581. case ('n'||'?')://下发反馈 失败
  582. /*memset(DVLreturn.data, 0, 32);
  583. DVLreturn.type = 'V';
  584. DVLreturn.len = 3;
  585. DVLreturn.data[0] = 'w';
  586. DVLreturn.data[1] = 'r';
  587. DVLreturn.data[2] = 'n';*/
  588. gcs().send_text(MAV_SEVERITY_INFO, "wrn");
  589. exitLoop = TRUE;//退出循环
  590. break;
  591. case 'c'://读配置成功
  592. /*memset(DVLreturn.data, 0, 32);
  593. DVLreturn.type = 'V';
  594. DVLreturn.len = DVL_RxCnt;
  595. for (int copyi = 0; copyi < DVL_RxCnt; copyi++)
  596. {
  597. DVLreturn.data[copyi] = RxDVL[copyi];
  598. }*/
  599. gcs().send_text(MAV_SEVERITY_INFO, "wrc");
  600. exitLoop = TRUE;//退出循环
  601. break;
  602. }
  603. DVL_RxCnt =0;//数据处理完了
  604. exitLoop = TRUE;//退出while
  605. memset(RxDVL, 0, sizeof(unsigned char)*240);
  606. }
  607. else{
  608. DVL_RxCnt =0;//校验错误
  609. //exitLoop = TRUE;//退出while
  610. memset(RxDVL, 0, sizeof(unsigned char)*240);
  611. }
  612. }
  613. else{
  614. DVL_RxCnt =0;
  615. //exitLoop = TRUE;//退出while
  616. //不是要接收数据的数据帧
  617. memset(RxDVL, 0, sizeof(unsigned char)*240);
  618. }
  619. }
  620. if(AP_HAL::micros() - readtime >800)//时间溢出0.8ms micros是微秒
  621. {//接收数据超时
  622. DVL_RxCnt=0;
  623. memset(RxDVL, 0, sizeof(unsigned char)*240);
  624. gcs().send_text(MAV_SEVERITY_INFO, " E read timeout");
  625. break;//退出while
  626. }
  627. }
  628. if (AP_HAL::millis() - DVLvalidtime>3000)//超过3秒没有可靠数据 millis是毫秒
  629. {
  630. DVLvalidtime = AP_HAL::micros();
  631. //gcs().send_text(MAV_SEVERITY_WARNING, " DVL lost valid data");
  632. }
  633. }
  634. int Sub::chartodec(unsigned char _ch){
  635. int dl = 0;
  636. if(_ch>='a' && _ch<='f'){
  637. dl = _ch-87;
  638. }else if(_ch>='0' && _ch<='9'){
  639. dl = _ch-48;
  640. }else{
  641. //不是数字
  642. }
  643. return dl;
  644. }