control_clean.cpp 15 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623
  1. #include "Sub.h"
  2. //目标姿态
  3. float maxspeed = 41.0;
  4. int16_t minspeed = 31;
  5. int16_t maxerrorspeed = 31;
  6. //float turnspeed = maxspeed - maxerror_f;
  7. Quaternion _attitude_target_quat;
  8. extern mavlink_rov_state_monitoring_t rov_message;
  9. bool Sub::clean_init()
  10. {
  11. pos_control.set_alt_target(0);
  12. motor1_speed_target =startval;//1500;
  13. motor2_speed_target =startval;//
  14. float _head =0;
  15. _head = (float)ahrs.yaw_sensor/100;
  16. //track
  17. track_head_gd = constrain_float(_head,0.0,360.0);
  18. last_roll = 0;
  19. last_pitch = 0;
  20. last_yaw = ahrs.yaw_sensor;
  21. //记录进入stable的YAW的当前值
  22. //yaw_press = (int16_t)(ahrs.yaw_sensor/100);//记住方位
  23. last_input_ms = AP_HAL::millis();
  24. track_reset();
  25. return true;
  26. }
  27. void Sub::track_reset(void){
  28. updowmgain =0.5;
  29. autoclean_command = FALSE;//自动刷网
  30. clean_bottom_command =FALSE;
  31. clean_bottom_flag = FALSE;
  32. autoclean_flag = FALSE;
  33. handclean = TRUE;
  34. turn_angle = 16.0;//20210622
  35. //----------------------
  36. track_motor_arm = 1;//履带停机标志
  37. //履带的初始方向位置 默认为水平方向的yaw值
  38. track_head_gd = 0;
  39. //履带停
  40. motor1_speed_target =startval;
  41. motor2_speed_target =startval;
  42. motors.pwm_track[0] = 1500;
  43. motors.pwm_track[1] = 1500;
  44. clean_mode =0;
  45. attitude_control.relax_attitude_controllers();//外置九轴YAW更新四元数
  46. last_roll = 0;
  47. last_pitch = 0;
  48. last_yaw = ahrs.yaw_sensor;
  49. //yaw_press = (int16_t)ahrs.yaw_sensor/100;//记住方位
  50. ahrs.get_quat_body_to_ned(_attitude_target_quat);
  51. }
  52. extern mavlink_data64_t rov_message2;
  53. extern mavlink_rov_control_t rov_control;
  54. void Sub::clean_run()
  55. {
  56. // if not armed set throttle to zero and exit immediately
  57. if (!motors.armed()) {
  58. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::GROUND_IDLE);
  59. attitude_control.set_throttle_out(0,true,g.throttle_filt);
  60. attitude_control.relax_attitude_controllers();//---------------------20210623
  61. PressLevel_f =5.0;//压力为0
  62. PressLevel = no;
  63. updowmgain =0.5;
  64. //-------------
  65. track_reset();
  66. return;
  67. }
  68. //推进器-------------------
  69. motors.set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
  70. motors.set_throttle(1.0-(float)PressLevel_f*0.1);//压力等级
  71. rov_message.pressure_level = int(PressLevel);
  72. motors.set_forward(0.0); //右侧摇杆,前推为+,后推为- 右履带的前进后退
  73. motors.set_lateral(0.0);//右侧摇杆 左推-,右推+
  74. motors.set_yaw(0.0);//左侧摇杆左推- 右推+
  75. motors.set_roll(0.0);
  76. motors.set_pitch(0.0);
  77. motors.set_yaw(0.0);
  78. static int j = 0;
  79. j++;
  80. if(j>800)
  81. {
  82. // gcs().send_text(MAV_SEVERITY_INFO, " track_limit %f\n",(float)rov_control.track_limit);
  83. j=0;
  84. }
  85. //最大速度-------------
  86. int16_t maxspeed_up=100;//这里是百分比0.9
  87. maxspeed_up = SRV_Channels::srv_channel(15)->get_trim()/100;
  88. maxspeed = (float)rov_control.track_limit;
  89. /*if(maxspeed_up<maxspeed)
  90. {
  91. maxspeed = maxspeed_up;
  92. }*/
  93. if(maxspeed_up >100)
  94. {
  95. maxspeed_up = 100;
  96. }
  97. maxspeed = maxspeed_up;
  98. maxspeed = constrain_float(maxspeed,30.0,100.0);
  99. //----------------------
  100. maxerrorspeed =SRV_Channels::srv_channel(15)->get_output_min()/100;//两个履带最大差速 ----------最深距离 厘米
  101. maxerrorspeed = constrain_int16(maxerrorspeed,20,maxspeed);
  102. minspeed =SRV_Channels::srv_channel(15)->get_output_max()/100;// 暂时用来做最小速度 -----最小水深
  103. minspeed = constrain_int16(minspeed,20,maxspeed);
  104. autoclean_flag_chose();//自动洗网的状态切换
  105. clean_net_joystick();//默认手动洗网
  106. clean_sidenet_auto();//按一下自动洗网使能,再按一下失能,回到手动洗网状态
  107. }
  108. void Sub::autoclean_flag_chose(void){
  109. if (autoclean_command == TRUE)
  110. {
  111. autoclean_flag = TRUE;
  112. }
  113. else{
  114. autoclean_flag = FALSE;
  115. }
  116. if (autoclean_flag == FALSE && clean_bottom_flag == FALSE)
  117. {
  118. handclean = TRUE;
  119. }
  120. else{
  121. handclean = FALSE;
  122. }
  123. }
  124. void Sub::clean_net_joystick(void)
  125. {
  126. float left =startval;
  127. float _turn =startval;
  128. int16_t motors1 =startval;
  129. int16_t motors2 =startval;
  130. if(handclean == TRUE ){
  131. //计算电机的 手动转速
  132. left = Constrate1(channel_forward->norm_input());//
  133. _turn = Constrate1(channel_yaw->norm_input());//
  134. motors1 = (int16_t)((left*maxspeed +_turn*maxerrorspeed));//
  135. motors2 = (int16_t)((left*maxspeed -_turn*maxerrorspeed));//
  136. if(_turn>0.1)
  137. {
  138. _turn =1.0;
  139. rov_message.turn = 3;
  140. }else if(_turn<-0.1){
  141. _turn =-1.0;
  142. rov_message.turn = 2;
  143. }else{
  144. rov_message.turn = 1;
  145. }
  146. if (left>0.1)
  147. {
  148. //前进
  149. if (motors1<minspeed)
  150. {
  151. motors1 =minspeed;
  152. }
  153. if (motors2<minspeed)
  154. {
  155. motors2 =minspeed;
  156. }
  157. }
  158. else if (left<-0.1)
  159. {
  160. //后退
  161. if (motors1>-minspeed)
  162. {
  163. motors1 =-minspeed;
  164. }
  165. if (motors2>-minspeed)
  166. {
  167. motors2 =-minspeed;
  168. }
  169. }
  170. else{
  171. if(fabsf(_turn)<0.1)
  172. {
  173. motors1 =0;
  174. motors2 =0;
  175. }
  176. else{
  177. motors1 = _turn*maxerrorspeed;//
  178. motors2 = -_turn*maxerrorspeed;//
  179. }
  180. }
  181. motors1=constrain_int16(motors1,-(int16_t)(maxspeed*0.65),maxspeed);
  182. motors2=constrain_int16(motors2,-(int16_t)(maxspeed*0.65),maxspeed);
  183. static int f = 0;
  184. f++;
  185. if(f>800)
  186. {
  187. gcs().send_text(MAV_SEVERITY_INFO, "rov_message.left_brush %d %d,%f",(int)minspeed,(int)maxerrorspeed,maxspeed);
  188. f=0;
  189. }
  190. //左摇杆前进后退的指示---------------
  191. if(left>0.1){
  192. track_motor_arm = 2;//前进
  193. }
  194. else if(left<-0.1){
  195. track_motor_arm = 0;
  196. }
  197. else{
  198. track_motor_arm=1;
  199. }
  200. rov_message.forward = track_motor_arm;
  201. //---------------------------
  202. //右摇杆 转向的控制
  203. if(fabsf(_turn)>0.1 )// 防抖
  204. {
  205. //转弯中 手动控制
  206. track_head_gd = (float)ahrs.yaw_sensor/100;//to show 20210611
  207. slowly_speed1(motor1_speed_target,motors1,1,3);
  208. slowly_speed2(motor2_speed_target,motors2,1,3);
  209. track_motor_arm =3;//left or right
  210. }
  211. else{
  212. //纯手动控制
  213. if(clean_mode == 0){
  214. slowly_speed1(motor1_speed_target,motors1,1,3);
  215. slowly_speed2(motor2_speed_target,motors2,1,3);
  216. static int kn1 = 0;
  217. kn1++;
  218. if(kn1>800)
  219. {
  220. //gcs().send_text(MAV_SEVERITY_WARNING, "left %f, turn %f %f %f\n",left,_turn,left*Speedmax_hand,_turn*maxerror);
  221. gcs().send_text(MAV_SEVERITY_WARNING, " speed_target %f %d %d ",left,motor2_speed_target,motor1_speed_target);
  222. kn1=0;
  223. }
  224. }else {
  225. }
  226. }
  227. motors.pwm_track[0] = 1500 + 400*motor1_speed_target/100;
  228. motors.pwm_track[1] = 1500 + 400*motor2_speed_target/100;
  229. }
  230. }
  231. void Sub::slowly_speed2(int16_t &p1, int16_t p2,int16_t step,int16_t per)
  232. {
  233. static int16_t countper = 0;
  234. countper++;
  235. if(countper>per){
  236. countper = 0;
  237. if (p1 > p2)
  238. {
  239. p1 -=step;
  240. }else if(p1 < p2){
  241. p1 +=step;
  242. }
  243. if (p2==startval && fabsf(p1-p2)<=step )
  244. {
  245. p1 =startval;
  246. }
  247. }
  248. else{
  249. }
  250. //p1 = constrain_int16(p1, -(Speedmax_hand+maxerror), Speedmax_hand+maxerror);
  251. p1 = constrain_int16(p1, -((int16_t)maxspeed), 100);
  252. static int j = 0;
  253. j++;
  254. if(j>800)
  255. {
  256. // gcs().send_text(MAV_SEVERITY_WARNING, " thrust%d %f ,%d,%d\n",i,thrust_in,thrust,last_thrust_pwm[i]);
  257. j=0;
  258. }
  259. }
  260. void Sub::slowly_speed1(int16_t &p1, int16_t p2,int16_t step,int16_t per)
  261. {
  262. static int16_t countper = 0;
  263. countper++;
  264. if(countper>per){
  265. countper = 0;
  266. if (p1 > p2)
  267. {
  268. p1 -=step;
  269. }else if(p1 < p2){
  270. p1 +=step;
  271. }
  272. if (p2==startval && fabsf(p1-p2)<=step )
  273. {
  274. p1 =startval;
  275. }
  276. }
  277. else{
  278. }
  279. //p1 = constrain_int16(p1, -(Speedmax_hand+maxerror), Speedmax_hand+maxerror);
  280. p1 = constrain_int16(p1, -((int16_t)maxspeed), 100);
  281. static int j = 0;
  282. j++;
  283. if(j>800)
  284. {
  285. // gcs().send_text(MAV_SEVERITY_WARNING, " thrust%d %f ,%d,%d\n",i,thrust_in,thrust,last_thrust_pwm[i]);
  286. j=0;
  287. }
  288. }
  289. float Sub::Constrate1(float d1)
  290. {//摇杆死区设置 0.06= 30/500
  291. if (fabsf(d1)*100<6)
  292. {
  293. return 0.0;
  294. }
  295. else{
  296. return d1;
  297. }
  298. }
  299. //extern mavlink_motor_feedback_t motor_feedback;
  300. extern mavlink_motor_speed_t mav_motor_speed;
  301. extern mavlink_rov_state_monitoring_t rov_message;
  302. void Sub::clean_sidenet_auto(void)
  303. {
  304. }
  305. //提取朝向误差并返回
  306. float Sub::get_yaw_error(float yaw_heading){
  307. //目标四元数
  308. Quaternion error_head;
  309. error_head.from_axis_angle(Vector3f(0, 0, yaw_heading*RAD_TO_DEG));
  310. _attitude_target_quat = _attitude_target_quat*error_head;
  311. //当前姿态
  312. Quaternion attitude_vehicle_quat;
  313. ahrs.get_quat_body_to_ned(attitude_vehicle_quat);
  314. //当前姿态Z轴
  315. Matrix3f att_to_rot_matrix; // rotation from the target body frame to the inertial frame.
  316. attitude_vehicle_quat.rotation_matrix(att_to_rot_matrix);
  317. Vector3f att_to_thrust_vec = att_to_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  318. //目标姿态Z轴
  319. Matrix3f att_from_rot_matrix; // rotation from the current body frame to the inertial frame.
  320. _attitude_target_quat.rotation_matrix(att_from_rot_matrix);
  321. Vector3f att_from_thrust_vec = att_from_rot_matrix * Vector3f(0.0f, 0.0f, 1.0f);
  322. Vector3f thrust_vec_cross = att_from_thrust_vec % att_to_thrust_vec;//得到轴
  323. float thrust_vec_dot = acosf(constrain_float(att_from_thrust_vec * att_to_thrust_vec, -1.0f, 1.0f));//得到角
  324. float thrust_vector_length = thrust_vec_cross.length();
  325. if (is_zero(thrust_vector_length) || is_zero(thrust_vec_dot)) {
  326. thrust_vec_cross = Vector3f(0, 0, 1);
  327. thrust_vec_dot = 0.0f;
  328. } else {
  329. thrust_vec_cross /= thrust_vector_length;
  330. }
  331. Quaternion error_lean;
  332. error_lean.from_axis_angle(thrust_vec_cross, thrust_vec_dot);// 地系下的从obj到half态的误差四元数
  333. Quaternion error_lean_body= attitude_vehicle_quat.inverse() * error_lean * attitude_vehicle_quat;//b系下的从obj到half态的误差四元数
  334. Quaternion lean_earth= attitude_vehicle_quat * error_lean_body ;//half态下的四元数
  335. Quaternion error_yaw= lean_earth.inverse() * _attitude_target_quat ;//yaw误差四元数
  336. Vector3f rotation;
  337. error_yaw.to_axis_angle(rotation);//得到轴角
  338. float yaw_error = rotation.z*RAD_TO_DEG;//得到yaw方位的误差
  339. return yaw_error;
  340. }
  341. void Sub::clean_sidenet_state(void){
  342. //-------------机器人头朝上-自动洗网-
  343. min_depth =SRV_Channels::srv_channel(11)->get_output_min();// 上端距离 厘米
  344. max_depth = SRV_Channels::srv_channel(11)->get_output_max();//最深距离 厘米
  345. int16_t depth_now =fabsf((int16_t)barometer.get_altitude())*100;
  346. if(autoclean_flag == FALSE)
  347. {//没有自动洗网 保存深度值
  348. autoclean_orgin =depth_now;
  349. autoclean_step = Orign;
  350. }else{
  351. int16_t depth_down=min_depth;
  352. static int8_t delayCnt = 0;
  353. int16_t depth_up = max_depth;
  354. static int8_t delayCnt2 = 0;
  355. switch(autoclean_step){
  356. case Orign:
  357. track_head_gd = 0;
  358. //起始位置位于中上部,先往下走,如果起始位置在中下部 先往上走 假设头向上
  359. if(fabsf(autoclean_orgin-min_depth)>fabsf(autoclean_orgin-max_depth)){
  360. track_motor_arm =2;//向前走
  361. autoclean_step = foward;
  362. }else{
  363. track_motor_arm =0;//向后走
  364. autoclean_step = backward;
  365. }
  366. break;
  367. case foward:
  368. //向前走 2
  369. if (track_motor_arm !=0 && depth_now<=min_depth)
  370. {//转折处 前走 或者 停 但深度小于设置值
  371. track_head_gd = turn_angle;//10度 转10度
  372. track_motor_arm = 1;//先停
  373. delayCnt++;
  374. if (delayCnt>100)//停后延时,400 HZ 理论是0.25秒
  375. {
  376. track_motor_arm = 0;
  377. delayCnt =0;
  378. }
  379. }else{
  380. }
  381. if (track_motor_arm == 0 && depth_now -depth_down>100)//相反方向走了xx cm
  382. {//切换到向后走
  383. track_head_gd = 0.0;//0度
  384. autoclean_step =backward;
  385. }
  386. break;
  387. case backward:
  388. //向后走kk
  389. if (track_motor_arm !=2 && depth_now>=max_depth)
  390. {//转折处 向前走或者停 深度大于设置的最大深度
  391. track_head_gd = -turn_angle;//-10度
  392. track_motor_arm = 1;//2;
  393. delayCnt2++;
  394. if (delayCnt2>100)
  395. {
  396. delayCnt2=0;
  397. track_motor_arm=2;
  398. }
  399. }
  400. else{
  401. }
  402. if (track_motor_arm == 2 && depth_up-depth_now>100)////相反方向走了xx cm
  403. {//切换到向前走
  404. track_head_gd = 0.0;
  405. autoclean_step =foward;//切换状态
  406. }
  407. break;
  408. default:
  409. track_motor_arm =1;
  410. track_head_gd=0.0;
  411. break;
  412. }
  413. }
  414. }
  415. void Sub::clean_sidenet_run(void)//自动洗测网
  416. {
  417. //水平方向还没有自动洗网,没有测试
  418. static int16_t motors1=0;
  419. static int16_t motors2=0;
  420. if (autoclean_flag == FALSE)
  421. {//没有自动洗网返回
  422. motors1=0;
  423. motors2=0;
  424. return;
  425. }
  426. //PID设置
  427. trackpid.p1 = attitude_control._thr_mix_man;
  428. trackpid.p2 = attitude_control._thr_mix_man;
  429. trackpid.i1 = attitude_control._thr_mix_max;
  430. trackpid.i2 = attitude_control._thr_mix_max;
  431. trackpid.d1 = attitude_control._thr_mix_min;
  432. trackpid.d2 = attitude_control._thr_mix_min;
  433. //1000-1500向前走,左履带1,右履带2,方向 右歪增大
  434. static int8_t per = 0;//分频数
  435. if (per >3)
  436. {//50HZ控制频率
  437. per = 0;
  438. track_pidcontrol(track_head_gd,motors1,motors2);
  439. }
  440. per++;
  441. slowly_speed1(motor1_speed_target,motors1,1,3);
  442. slowly_speed2(motor2_speed_target,motors2,1,3);
  443. }
  444. // 不同方向上的履带的PID调用 以及缓加缓减
  445. void Sub::track_pidcontrol(float _targethead,int16_t &_motor1,int16_t &_motor2){
  446. int16_t motors1=startval;
  447. int16_t motors2 =startval;
  448. uint32_t nowtime=AP_HAL::micros();
  449. static uint32_t lasttime = nowtime;//用于换向延时防止抱死
  450. float error = get_yaw_error(_targethead);
  451. if (track_motor_arm ==0)
  452. {//后走
  453. if (nowtime - lasttime <500000)//500ms T1
  454. {//防抱死
  455. motors1 = startval;
  456. motors2 = startval;
  457. }
  458. else{
  459. motors1 = constrain_int16(-Speedmax+trackpid.updatePID1(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  460. motors2 = constrain_int16(-Speedmax+trackpid.updatePID2(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  461. }
  462. }
  463. else if (track_motor_arm ==1)
  464. {//停
  465. lasttime = AP_HAL::micros();
  466. motors1 = startval;
  467. motors2 =startval;
  468. }
  469. else if (track_motor_arm ==2)
  470. {//前走
  471. if (nowtime - lasttime <500000)//500ms T1
  472. {//防抱死
  473. motors1 =startval;
  474. motors2 = startval;
  475. }
  476. else{
  477. motors1 = constrain_int16(Speedmax+trackpid.updatePID1(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  478. motors2 = constrain_int16(Speedmax+trackpid.updatePID2(0,0,error,(float)Speedmax),-Speedmax,Speedmax);
  479. }
  480. }
  481. _motor1 = motors1;
  482. _motor2 = motors2;
  483. }