control_clean.cpp 14 KB

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