control_clean.cpp 15 KB

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