control_clean.cpp 15 KB

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