control_clean.cpp 16 KB

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